From 237c8a614d3b834f9f9cc5e0622a3ecfca00142f Mon Sep 17 00:00:00 2001 From: imoted Date: Mon, 25 Jul 2022 23:00:31 +0900 Subject: [PATCH 01/10] add the modified message conversion --- .../ros_awsiot_agent/message_conversion.py | 239 ++++++++++++++++++ .../src/ros_awsiot_agent/mqtt2ros.py | 3 +- 2 files changed, 241 insertions(+), 1 deletion(-) create mode 100644 ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py diff --git a/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py b/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py new file mode 100644 index 0000000..134f4ad --- /dev/null +++ b/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py @@ -0,0 +1,239 @@ +#!/usr/bin/env python3 +# Software License Agreement (BSD License) +# +# Copyright (c) 2012, Willow Garage, Inc. +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# * Redistributions in binary form must reproduce the above +# copyright notice, this list of conditions and the following +# disclaimer in the documentation and/or other materials provided +# with the distribution. +# * Neither the name of Willow Garage, Inc. nor the names of its +# contributors may be used to endorse or promote products derived +# from this software without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. + +from __future__ import print_function +import rospy + +from rosbridge_library.internal import ros_loader + +import re +from base64 import standard_b64encode, standard_b64decode + +from rosbridge_library.util import string_types, bson + + +type_map = { + "bool": ["bool"], + "int": [ + "int8", + "byte", + "uint8", + "char", + "int16", + "uint16", + "int32", + "uint32", + "int64", + "uint64", + "float32", + "float64", + ], + "float": ["float32", "float64"], + "str": ["string"], +} +primitive_types = [bool, int, float] +python2 = False + +list_types = [list, tuple] +ros_time_types = ["time", "duration"] +ros_primitive_types = [ + "bool", + "byte", + "char", + "int8", + "uint8", + "int16", + "uint16", + "int32", + "uint32", + "int64", + "uint64", + "float32", + "float64", + "string", +] +ros_header_types = ["Header", "std_msgs/Header", "roslib/Header"] +ros_binary_types = ["uint8[]", "char[]"] +list_braces = re.compile(r"\[[^\]]*\]") +ros_binary_types_list_braces = [ + ("uint8[]", re.compile(r"uint8\[[^\]]*\]")), + ("char[]", re.compile(r"char\[[^\]]*\]")), +] + + + +class FieldTypeMismatchException(Exception): + def __init__(self, roottype, fields, expected_type, found_type): + if roottype == expected_type: + Exception.__init__( + self, + "Expected a JSON object for type %s but received a %s" + % (roottype, found_type), + ) + else: + Exception.__init__( + self, + "%s message requires a %s for field %s, but got a %s" + % (roottype, expected_type, ".".join(fields), found_type), + ) + + +def populate_instance(msg, inst): + """Returns an instance of the provided class, with its fields populated + according to the values in msg""" + return _to_inst(msg, inst._type, inst._type, inst) + + +def _to_inst(msg, rostype, roottype, inst=None, stack=[]): + # Check if it's uint8[], and if it's a string, try to b64decode + for binary_type, expression in ros_binary_types_list_braces: + if expression.sub(binary_type, rostype) in ros_binary_types: + return _to_binary_inst(msg) + + # Check the type for time or rostime + if rostype in ros_time_types: + return _to_time_inst(msg, rostype, inst) + + # Check to see whether this is a primitive type + if rostype in ros_primitive_types: + return _to_primitive_inst(msg, rostype, roottype, stack) + + # Check whether we're dealing with a list type + if inst is not None and type(inst) in list_types: + return _to_list_inst(msg, rostype, roottype, inst, stack) + + # Otherwise, the type has to be a full ros msg type, so msg must be a dict + if inst is None: + inst = ros_loader.get_message_instance(rostype) + + return _to_object_inst(msg, rostype, roottype, inst, stack) + + +def _to_binary_inst(msg): + if type(msg) in string_types: + try: + return standard_b64decode(msg) + except: + return msg + else: + try: + return bytes(bytearray(msg)) + except: + return msg + + +def _to_time_inst(msg, rostype, inst=None): + # Create an instance if we haven't been provided with one + if rostype == "time" and msg == "now": + return rospy.get_rostime() + + if inst is None: + if rostype == "time": + inst = rospy.rostime.Time() + elif rostype == "duration": + inst = rospy.rostime.Duration() + else: + return None + + # Copy across the fields + for field in ["secs", "nsecs"]: + try: + if field in msg: + setattr(inst, field, msg[field]) + except TypeError: + continue + + return inst + + +def _to_primitive_inst(msg, rostype, roottype, stack): + # Typecheck the msg + msgtype = type(msg) + if msgtype in primitive_types and rostype in type_map[msgtype.__name__]: + return msg + elif msgtype in string_types and rostype in type_map[msgtype.__name__]: + return msg.encode("utf-8", "ignore") if python2 else msg + raise FieldTypeMismatchException(roottype, stack, rostype, msgtype) + + +def _to_list_inst(msg, rostype, roottype, inst, stack): + # Typecheck the msg + if type(msg) not in list_types: + raise FieldTypeMismatchException(roottype, stack, rostype, type(msg)) + + # Can duck out early if the list is empty + if len(msg) == 0: + return [] + + # Remove the list indicators from the rostype + rostype = list_braces.sub("", rostype) + + # Call to _to_inst for every element of the list + return [_to_inst(x, rostype, roottype, None, stack) for x in msg] + + +def _to_object_inst(msg, rostype, roottype, inst, stack): + # Typecheck the msg + if type(msg) is not dict: + raise FieldTypeMismatchException(roottype, stack, rostype, type(msg)) + + # Substitute the correct time if we're an std_msgs/Header + try: + if rostype in ros_header_types: + cur_time = rospy.get_rostime() + # copy attributes of global Time obj to inst.stamp + inst.stamp.secs = cur_time.secs + inst.stamp.nsecs = cur_time.nsecs + except rospy.exceptions.ROSInitException as e: + rospy.logdebug("Not substituting the correct header time: %s" % e) + + inst_fields = dict(zip(inst.__slots__, inst._slot_types)) + + for field_name in msg: + # Add this field to the field stack + field_stack = stack + [field_name] + + # pass the field if the msg contains a bad field + if not field_name in inst_fields: + continue + + field_rostype = inst_fields[field_name] + field_inst = getattr(inst, field_name) + + field_value = _to_inst( + msg[field_name], field_rostype, roottype, field_inst, field_stack + ) + + setattr(inst, field_name, field_value) + + return inst diff --git a/ros_awsiot_agent/src/ros_awsiot_agent/mqtt2ros.py b/ros_awsiot_agent/src/ros_awsiot_agent/mqtt2ros.py index bee53cb..207bad1 100755 --- a/ros_awsiot_agent/src/ros_awsiot_agent/mqtt2ros.py +++ b/ros_awsiot_agent/src/ros_awsiot_agent/mqtt2ros.py @@ -8,9 +8,10 @@ import rospy from awsiotclient import mqtt, pubsub from ros_awsiot_agent import set_module_logger -from rosbridge_library.internal.message_conversion import populate_instance from rosbridge_library.internal.ros_loader import get_message_class +from message_conversion import populate_instance + set_module_logger(modname="awsiotclient", level=logging.WARN) From 66cde97142bb9895c1d2e7e0931ab6220552abeb Mon Sep 17 00:00:00 2001 From: imoted Date: Tue, 26 Jul 2022 10:55:33 +0900 Subject: [PATCH 02/10] fix flake8 alert --- .../src/ros_awsiot_agent/message_conversion.py | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py b/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py index 134f4ad..ec53a37 100644 --- a/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py +++ b/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py @@ -37,9 +37,9 @@ from rosbridge_library.internal import ros_loader import re -from base64 import standard_b64encode, standard_b64decode +from base64 import standard_b64decode -from rosbridge_library.util import string_types, bson +from rosbridge_library.util import string_types type_map = { @@ -91,7 +91,6 @@ ] - class FieldTypeMismatchException(Exception): def __init__(self, roottype, fields, expected_type, found_type): if roottype == expected_type: @@ -143,12 +142,12 @@ def _to_binary_inst(msg): if type(msg) in string_types: try: return standard_b64decode(msg) - except: + except TypeError: return msg else: try: return bytes(bytearray(msg)) - except: + except TypeError: return msg @@ -192,7 +191,7 @@ def _to_list_inst(msg, rostype, roottype, inst, stack): raise FieldTypeMismatchException(roottype, stack, rostype, type(msg)) # Can duck out early if the list is empty - if len(msg) == 0: + if not msg: return [] # Remove the list indicators from the rostype @@ -224,7 +223,7 @@ def _to_object_inst(msg, rostype, roottype, inst, stack): field_stack = stack + [field_name] # pass the field if the msg contains a bad field - if not field_name in inst_fields: + if field_name not in inst_fields: continue field_rostype = inst_fields[field_name] From 2c14b493ecb866f27ae176bcba3cbfb5680c9e8e Mon Sep 17 00:00:00 2001 From: imoted Date: Tue, 26 Jul 2022 16:17:49 +0900 Subject: [PATCH 03/10] undo the deleted function in message conversion --- .../ros_awsiot_agent/message_conversion.py | 200 ++++++++++++------ 1 file changed, 135 insertions(+), 65 deletions(-) mode change 100644 => 100755 ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py diff --git a/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py b/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py old mode 100644 new mode 100755 index ec53a37..55deb0e --- a/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py +++ b/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py @@ -1,4 +1,4 @@ -#!/usr/bin/env python3 +#!/usr/bin/env python # Software License Agreement (BSD License) # # Copyright (c) 2012, Willow Garage, Inc. @@ -36,83 +36,154 @@ from rosbridge_library.internal import ros_loader +import math import re -from base64 import standard_b64decode - -from rosbridge_library.util import string_types - - -type_map = { - "bool": ["bool"], - "int": [ - "int8", - "byte", - "uint8", - "char", - "int16", - "uint16", - "int32", - "uint32", - "int64", - "uint64", - "float32", - "float64", - ], - "float": ["float32", "float64"], - "str": ["string"], -} -primitive_types = [bool, int, float] -python2 = False +from base64 import standard_b64encode, standard_b64decode + +from rosbridge_library.util import string_types, bson + +import sys +if sys.version_info >= (3, 0): + type_map = { + "bool": ["bool"], + "int": ["int8", "byte", "uint8", "char", + "int16", "uint16", "int32", "uint32", + "int64", "uint64", "float32", "float64"], + "float": ["float32", "float64"], + "str": ["string"] + } + primitive_types = [bool, int, float] + python2 = False +else: + type_map = { + "bool": ["bool"], + "int": ["int8", "byte", "uint8", "char", + "int16", "uint16", "int32", "uint32", + "int64", "uint64", "float32", "float64"], + "float": ["float32", "float64"], + "str": ["string"], + "unicode": ["string"], + "long": ["int64", "uint64"] + } + primitive_types = [bool, int, long, float] # noqa: F821 + python2 = True list_types = [list, tuple] ros_time_types = ["time", "duration"] -ros_primitive_types = [ - "bool", - "byte", - "char", - "int8", - "uint8", - "int16", - "uint16", - "int32", - "uint32", - "int64", - "uint64", - "float32", - "float64", - "string", -] +ros_primitive_types = ["bool", "byte", "char", "int8", "uint8", "int16", + "uint16", "int32", "uint32", "int64", "uint64", + "float32", "float64", "string"] ros_header_types = ["Header", "std_msgs/Header", "roslib/Header"] ros_binary_types = ["uint8[]", "char[]"] -list_braces = re.compile(r"\[[^\]]*\]") -ros_binary_types_list_braces = [ - ("uint8[]", re.compile(r"uint8\[[^\]]*\]")), - ("char[]", re.compile(r"char\[[^\]]*\]")), -] +list_braces = re.compile(r'\[[^\]]*\]') +ros_binary_types_list_braces = [("uint8[]", re.compile(r'uint8\[[^\]]*\]')), + ("char[]", re.compile(r'char\[[^\]]*\]'))] + +binary_encoder = None +bson_only_mode = None + + +def get_encoder(): + global binary_encoder,bson_only_mode + if binary_encoder is None: + binary_encoder_type = rospy.get_param('~binary_encoder', 'default') + bson_only_mode = rospy.get_param('~bson_only_mode', False) + + if binary_encoder_type == 'bson' or bson_only_mode: + binary_encoder = bson.Binary + elif binary_encoder_type == 'default' or binary_encoder_type == 'b64': + binary_encoder = standard_b64encode + else: + print("Unknown encoder type '%s'"%binary_encoder_type) + exit(0) + return binary_encoder + + +class InvalidMessageException(Exception): + def __init__(self, inst): + Exception.__init__(self, "Unable to extract message values from %s instance" % type(inst).__name__) + + +class NonexistentFieldException(Exception): + def __init__(self, basetype, fields): + Exception.__init__(self, "Message type %s does not have a field %s" % (basetype, '.'.join(fields))) class FieldTypeMismatchException(Exception): def __init__(self, roottype, fields, expected_type, found_type): if roottype == expected_type: - Exception.__init__( - self, - "Expected a JSON object for type %s but received a %s" - % (roottype, found_type), - ) + Exception.__init__(self, "Expected a JSON object for type %s but received a %s" % (roottype, found_type)) else: - Exception.__init__( - self, - "%s message requires a %s for field %s, but got a %s" - % (roottype, expected_type, ".".join(fields), found_type), - ) + Exception.__init__(self, "%s message requires a %s for field %s, but got a %s" % (roottype, expected_type, '.'.join(fields), found_type)) + + +def extract_values(inst): + rostype = getattr(inst, "_type", None) + if rostype is None: + raise InvalidMessageException(inst=inst) + return _from_inst(inst, rostype) def populate_instance(msg, inst): - """Returns an instance of the provided class, with its fields populated - according to the values in msg""" + """ Returns an instance of the provided class, with its fields populated + according to the values in msg """ return _to_inst(msg, inst._type, inst._type, inst) +def _from_inst(inst, rostype): + global bson_only_mode + # Special case for uint8[], we encode the string + for binary_type, expression in ros_binary_types_list_braces: + if expression.sub(binary_type, rostype) in ros_binary_types: + encoded = get_encoder()(inst) + return encoded if python2 else encoded.decode('ascii') + + # Check for time or duration + if rostype in ros_time_types: + return {"secs": inst.secs, "nsecs": inst.nsecs} + + if(bson_only_mode is None):bson_only_mode = rospy.get_param('~bson_only_mode', False) + # Check for primitive types + if rostype in ros_primitive_types: + #JSON does not support Inf and NaN. They are mapped to None and encoded as null + if (not bson_only_mode) and (rostype in ["float32", "float64"]): + if math.isnan(inst) or math.isinf(inst): + return None + return inst + + # Check if it's a list or tuple + if type(inst) in list_types: + return _from_list_inst(inst, rostype) + + # Assume it's otherwise a full ros msg object + return _from_object_inst(inst, rostype) + + +def _from_list_inst(inst, rostype): + # Can duck out early if the list is empty + if len(inst) == 0: + return [] + + # Remove the list indicators from the rostype + rostype = list_braces.sub("", rostype) + + # Shortcut for primitives + if rostype in ros_primitive_types and rostype not in ["float32", "float64"]: + return list(inst) + + # Call to _to_inst for every element of the list + return [_from_inst(x, rostype) for x in inst] + + +def _from_object_inst(inst, rostype): + # Create an empty dict then populate with values from the inst + msg = {} + for field_name, field_rostype in zip(inst.__slots__, inst._slot_types): + field_inst = getattr(inst, field_name) + msg[field_name] = _from_inst(field_inst, field_rostype) + return msg + + def _to_inst(msg, rostype, roottype, inst=None, stack=[]): # Check if it's uint8[], and if it's a string, try to b64decode for binary_type, expression in ros_binary_types_list_braces: @@ -191,7 +262,7 @@ def _to_list_inst(msg, rostype, roottype, inst, stack): raise FieldTypeMismatchException(roottype, stack, rostype, type(msg)) # Can duck out early if the list is empty - if not msg: + if len(msg) == 0: return [] # Remove the list indicators from the rostype @@ -222,16 +293,15 @@ def _to_object_inst(msg, rostype, roottype, inst, stack): # Add this field to the field stack field_stack = stack + [field_name] - # pass the field if the msg contains a bad field + # Raise an exception if the msg contains a bad field if field_name not in inst_fields: continue field_rostype = inst_fields[field_name] field_inst = getattr(inst, field_name) - field_value = _to_inst( - msg[field_name], field_rostype, roottype, field_inst, field_stack - ) + field_value = _to_inst(msg[field_name], field_rostype, + roottype, field_inst, field_stack) setattr(inst, field_name, field_value) From 533fafbbed0b256f752e2c2a6e3b25547a4461a7 Mon Sep 17 00:00:00 2001 From: imoted Date: Tue, 26 Jul 2022 16:39:36 +0900 Subject: [PATCH 04/10] apply the formatter --- .../ros_awsiot_agent/message_conversion.py | 130 +++++++++++++----- 1 file changed, 92 insertions(+), 38 deletions(-) diff --git a/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py b/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py index 55deb0e..74c4cdf 100755 --- a/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py +++ b/ros_awsiot_agent/src/ros_awsiot_agent/message_conversion.py @@ -43,78 +43,130 @@ from rosbridge_library.util import string_types, bson import sys + if sys.version_info >= (3, 0): type_map = { - "bool": ["bool"], - "int": ["int8", "byte", "uint8", "char", - "int16", "uint16", "int32", "uint32", - "int64", "uint64", "float32", "float64"], - "float": ["float32", "float64"], - "str": ["string"] + "bool": ["bool"], + "int": [ + "int8", + "byte", + "uint8", + "char", + "int16", + "uint16", + "int32", + "uint32", + "int64", + "uint64", + "float32", + "float64", + ], + "float": ["float32", "float64"], + "str": ["string"], } primitive_types = [bool, int, float] python2 = False else: type_map = { - "bool": ["bool"], - "int": ["int8", "byte", "uint8", "char", - "int16", "uint16", "int32", "uint32", - "int64", "uint64", "float32", "float64"], - "float": ["float32", "float64"], - "str": ["string"], - "unicode": ["string"], - "long": ["int64", "uint64"] + "bool": ["bool"], + "int": [ + "int8", + "byte", + "uint8", + "char", + "int16", + "uint16", + "int32", + "uint32", + "int64", + "uint64", + "float32", + "float64", + ], + "float": ["float32", "float64"], + "str": ["string"], + "unicode": ["string"], + "long": ["int64", "uint64"], } primitive_types = [bool, int, long, float] # noqa: F821 python2 = True list_types = [list, tuple] ros_time_types = ["time", "duration"] -ros_primitive_types = ["bool", "byte", "char", "int8", "uint8", "int16", - "uint16", "int32", "uint32", "int64", "uint64", - "float32", "float64", "string"] +ros_primitive_types = [ + "bool", + "byte", + "char", + "int8", + "uint8", + "int16", + "uint16", + "int32", + "uint32", + "int64", + "uint64", + "float32", + "float64", + "string", +] ros_header_types = ["Header", "std_msgs/Header", "roslib/Header"] ros_binary_types = ["uint8[]", "char[]"] -list_braces = re.compile(r'\[[^\]]*\]') -ros_binary_types_list_braces = [("uint8[]", re.compile(r'uint8\[[^\]]*\]')), - ("char[]", re.compile(r'char\[[^\]]*\]'))] +list_braces = re.compile(r"\[[^\]]*\]") +ros_binary_types_list_braces = [ + ("uint8[]", re.compile(r"uint8\[[^\]]*\]")), + ("char[]", re.compile(r"char\[[^\]]*\]")), +] binary_encoder = None bson_only_mode = None def get_encoder(): - global binary_encoder,bson_only_mode + global binary_encoder, bson_only_mode if binary_encoder is None: - binary_encoder_type = rospy.get_param('~binary_encoder', 'default') - bson_only_mode = rospy.get_param('~bson_only_mode', False) + binary_encoder_type = rospy.get_param("~binary_encoder", "default") + bson_only_mode = rospy.get_param("~bson_only_mode", False) - if binary_encoder_type == 'bson' or bson_only_mode: + if binary_encoder_type == "bson" or bson_only_mode: binary_encoder = bson.Binary - elif binary_encoder_type == 'default' or binary_encoder_type == 'b64': - binary_encoder = standard_b64encode + elif binary_encoder_type == "default" or binary_encoder_type == "b64": + binary_encoder = standard_b64encode else: - print("Unknown encoder type '%s'"%binary_encoder_type) + print("Unknown encoder type '%s'" % binary_encoder_type) exit(0) return binary_encoder class InvalidMessageException(Exception): def __init__(self, inst): - Exception.__init__(self, "Unable to extract message values from %s instance" % type(inst).__name__) + Exception.__init__( + self, + "Unable to extract message values from %s instance" % type(inst).__name__, + ) class NonexistentFieldException(Exception): def __init__(self, basetype, fields): - Exception.__init__(self, "Message type %s does not have a field %s" % (basetype, '.'.join(fields))) + Exception.__init__( + self, + "Message type %s does not have a field %s" % (basetype, ".".join(fields)), + ) class FieldTypeMismatchException(Exception): def __init__(self, roottype, fields, expected_type, found_type): if roottype == expected_type: - Exception.__init__(self, "Expected a JSON object for type %s but received a %s" % (roottype, found_type)) + Exception.__init__( + self, + "Expected a JSON object for type %s but received a %s" + % (roottype, found_type), + ) else: - Exception.__init__(self, "%s message requires a %s for field %s, but got a %s" % (roottype, expected_type, '.'.join(fields), found_type)) + Exception.__init__( + self, + "%s message requires a %s for field %s, but got a %s" + % (roottype, expected_type, ".".join(fields), found_type), + ) def extract_values(inst): @@ -125,8 +177,8 @@ def extract_values(inst): def populate_instance(msg, inst): - """ Returns an instance of the provided class, with its fields populated - according to the values in msg """ + """Returns an instance of the provided class, with its fields populated + according to the values in msg""" return _to_inst(msg, inst._type, inst._type, inst) @@ -136,16 +188,17 @@ def _from_inst(inst, rostype): for binary_type, expression in ros_binary_types_list_braces: if expression.sub(binary_type, rostype) in ros_binary_types: encoded = get_encoder()(inst) - return encoded if python2 else encoded.decode('ascii') + return encoded if python2 else encoded.decode("ascii") # Check for time or duration if rostype in ros_time_types: return {"secs": inst.secs, "nsecs": inst.nsecs} - if(bson_only_mode is None):bson_only_mode = rospy.get_param('~bson_only_mode', False) + if bson_only_mode is None: + bson_only_mode = rospy.get_param("~bson_only_mode", False) # Check for primitive types if rostype in ros_primitive_types: - #JSON does not support Inf and NaN. They are mapped to None and encoded as null + # JSON does not support Inf and NaN. They are mapped to None and encoded as null if (not bson_only_mode) and (rostype in ["float32", "float64"]): if math.isnan(inst) or math.isinf(inst): return None @@ -300,8 +353,9 @@ def _to_object_inst(msg, rostype, roottype, inst, stack): field_rostype = inst_fields[field_name] field_inst = getattr(inst, field_name) - field_value = _to_inst(msg[field_name], field_rostype, - roottype, field_inst, field_stack) + field_value = _to_inst( + msg[field_name], field_rostype, roottype, field_inst, field_stack + ) setattr(inst, field_name, field_value) From 9843c533bca88b3547fbf2161b0ed75168bb81d6 Mon Sep 17 00:00:00 2001 From: imoted Date: Tue, 26 Jul 2022 16:40:56 +0900 Subject: [PATCH 05/10] add test launch and unittest file for messsage conversion --- ros_awsiot_agent/test/message_conversion.test | 3 + .../test/test_message_conversion.py | 337 ++++++++++++++++++ 2 files changed, 340 insertions(+) create mode 100644 ros_awsiot_agent/test/message_conversion.test create mode 100755 ros_awsiot_agent/test/test_message_conversion.py diff --git a/ros_awsiot_agent/test/message_conversion.test b/ros_awsiot_agent/test/message_conversion.test new file mode 100644 index 0000000..c7ae722 --- /dev/null +++ b/ros_awsiot_agent/test/message_conversion.test @@ -0,0 +1,3 @@ + + + diff --git a/ros_awsiot_agent/test/test_message_conversion.py b/ros_awsiot_agent/test/test_message_conversion.py new file mode 100755 index 0000000..32e509c --- /dev/null +++ b/ros_awsiot_agent/test/test_message_conversion.py @@ -0,0 +1,337 @@ +#!/usr/bin/env python3 +from __future__ import print_function +import sys +import rospy +import rosunit +import unittest +from json import loads, dumps + +try: + from cStringIO import StringIO # Python 2.x +except ImportError: + from io import BytesIO as StringIO # Python 3.x + + +from src.ros_awsiot_agent import message_conversion as c +from rosbridge_library.internal import ros_loader +from base64 import standard_b64encode, standard_b64decode + +if sys.version_info >= (3, 0): + string_types = (str,) +else: + string_types = (str, unicode) # noqa: F821 + + +PKG = 'rosbridge_library' +NAME = 'test_message_conversion' + + +class TestMessageConversion(unittest.TestCase): + + def setUp(self): + rospy.init_node(NAME) + + def validate_instance(self, inst1): + """ Serializes and deserializes the inst to typecheck and ensure that + instances are correct """ + # _check_types() skipped because: https://github.com/ros/genpy/issues/122 + #inst1._check_types() + buff = StringIO() + inst1.serialize(buff) + inst2 = type(inst1)() + inst2.deserialize(buff.getvalue()) + self.assertEqual(inst1, inst2) + #inst2._check_types() + + def msgs_equal(self, msg1, msg2): + if type(msg1) in string_types and type(msg2) in string_types: + pass + else: + self.assertEqual(type(msg1), type(msg2)) + if type(msg1) in c.list_types: + for x, y in zip(msg1, msg2): + self.msgs_equal(x, y) + elif type(msg1) in c.primitive_types or type(msg1) in c.string_types: + self.assertEqual(msg1, msg2) + else: + for x in msg1: + self.assertTrue(x in msg2) + for x in msg2: + self.assertTrue(x in msg1) + for x in msg1: + self.msgs_equal(msg1[x], msg2[x]) + + def do_primitive_test(self, data_value, msgtype): + for msg in [{"data": data_value}, loads(dumps({"data": data_value}))]: + inst = ros_loader.get_message_instance(msgtype) + c.populate_instance(msg, inst) + self.assertEqual(inst.data, data_value) + self.validate_instance(inst) + extracted = c.extract_values(inst) + for msg2 in [extracted, loads(dumps(extracted))]: + self.msgs_equal(msg, msg2) + self.assertEqual(msg["data"], msg2["data"]) + self.assertEqual(msg2["data"], inst.data) + + def do_test(self, orig_msg, msgtype): + for msg in [orig_msg, loads(dumps(orig_msg))]: + inst = ros_loader.get_message_instance(msgtype) + c.populate_instance(msg, inst) + self.validate_instance(inst) + extracted = c.extract_values(inst) + for msg2 in [extracted, loads(dumps(extracted))]: + self.msgs_equal(msg, msg2) + + def test_int_primitives(self): + # Test raw primitives + for msg in range(-100, 100): + for rostype in ["int8", "int16", "int32", "int64"]: + self.assertEqual(c._to_primitive_inst(msg, rostype, rostype, []), msg) + self.assertEqual(c._to_inst(msg, rostype, rostype), msg) + # Test raw primitives + for msg in range(0, 200): + for rostype in ["uint8", "uint16", "uint32", "uint64"]: + self.assertEqual(c._to_primitive_inst(msg, rostype, rostype, []), msg) + self.assertEqual(c._to_inst(msg, rostype, rostype), msg) + + def test_bool_primitives(self): + self.assertTrue(c._to_primitive_inst(True, "bool", "bool", [])) + self.assertTrue(c._to_inst(True, "bool", "bool")) + self.assertFalse(c._to_primitive_inst(False, "bool", "bool", [])) + self.assertFalse(c._to_inst(False, "bool", "bool")) + + def test_float_primitives(self): + for msg in [0.12341234 + i for i in range(-100, 100)]: + for rostype in ["float32", "float64"]: + self.assertEqual(c._to_primitive_inst(msg, rostype, rostype, []), msg) + self.assertEqual(c._to_inst(msg, rostype, rostype), msg) + c._to_inst(msg, rostype, rostype) + + def test_float_special_cases(self): + for msg in [1e9999999, -1e9999999, float('nan')]: + for rostype in ["float32", "float64"]: + self.assertEqual(c._from_inst(msg, rostype), None) + self.assertEqual(dumps({"data":c._from_inst(msg, rostype)}), "{\"data\": null}") + + def test_signed_int_base_msgs(self): + int8s = range(-127, 128) + for int8 in int8s: + self.do_primitive_test(int8, "std_msgs/Byte") + self.do_primitive_test(int8, "std_msgs/Int8") + self.do_primitive_test(int8, "std_msgs/Int16") + self.do_primitive_test(int8, "std_msgs/Int32") + self.do_primitive_test(int8, "std_msgs/Int64") + + int16s = [-32767, 32767] + for int16 in int16s: + self.do_primitive_test(int16, "std_msgs/Int16") + self.do_primitive_test(int16, "std_msgs/Int32") + self.do_primitive_test(int16, "std_msgs/Int64") + self.assertRaises(Exception, self.do_primitive_test, int16, "std_msgs/Byte") + self.assertRaises(Exception, self.do_primitive_test, int16, "std_msgs/Int8") + + int32s = [-2147483647, 2147483647] + for int32 in int32s: + self.do_primitive_test(int32, "std_msgs/Int32") + self.do_primitive_test(int32, "std_msgs/Int64") + self.assertRaises(Exception, self.do_primitive_test, int32, "std_msgs/Byte") + self.assertRaises(Exception, self.do_primitive_test, int32, "std_msgs/Int8") + self.assertRaises(Exception, self.do_primitive_test, int32, "std_msgs/Int16") + + int64s = [-9223372036854775807, 9223372036854775807] + for int64 in int64s: + self.do_primitive_test(int64, "std_msgs/Int64") + self.assertRaises(Exception, self.do_primitive_test, int64, "std_msgs/Byte") + self.assertRaises(Exception, self.do_primitive_test, int64, "std_msgs/Int8") + self.assertRaises(Exception, self.do_primitive_test, int64, "std_msgs/Int16") + self.assertRaises(Exception, self.do_primitive_test, int64, "std_msgs/Int32") + + def test_unsigned_int_base_msgs(self): + int8s = range(0, 256) + for int8 in int8s: + self.do_primitive_test(int8, "std_msgs/Char") + self.do_primitive_test(int8, "std_msgs/UInt8") + self.do_primitive_test(int8, "std_msgs/UInt16") + self.do_primitive_test(int8, "std_msgs/UInt32") + self.do_primitive_test(int8, "std_msgs/UInt64") + + int16s = [32767, 32768, 65535] + for int16 in int16s: + self.do_primitive_test(int16, "std_msgs/UInt16") + self.do_primitive_test(int16, "std_msgs/UInt32") + self.do_primitive_test(int16, "std_msgs/UInt64") + self.assertRaises(Exception, self.do_primitive_test, int16, "std_msgs/Char") + self.assertRaises(Exception, self.do_primitive_test, int16, "std_msgs/UInt8") + + int32s = [2147483647, 2147483648, 4294967295] + for int32 in int32s: + self.do_primitive_test(int32, "std_msgs/UInt32") + self.do_primitive_test(int32, "std_msgs/UInt64") + self.assertRaises(Exception, self.do_primitive_test, int32, "std_msgs/Char") + self.assertRaises(Exception, self.do_primitive_test, int32, "std_msgs/UInt8") + self.assertRaises(Exception, self.do_primitive_test, int32, "std_msgs/UInt16") + + int64s = [4294967296, 9223372036854775807, 9223372036854775808, + 18446744073709551615] + for int64 in int64s: + self.do_primitive_test(int64, "std_msgs/UInt64") + self.assertRaises(Exception, self.do_primitive_test, int64, "std_msgs/Char") + self.assertRaises(Exception, self.do_primitive_test, int64, "std_msgs/UInt8") + self.assertRaises(Exception, self.do_primitive_test, int64, "std_msgs/UInt16") + self.assertRaises(Exception, self.do_primitive_test, int64, "std_msgs/UInt32") + + def test_bool_base_msg(self): + self.do_primitive_test(True, "std_msgs/Bool") + self.do_primitive_test(False, "std_msgs/Bool") + + def test_string_base_msg(self): + for x in c.ros_primitive_types: + self.do_primitive_test(x, "std_msgs/String") + + def test_time_msg(self): + msg = {"data": {"secs": 3, "nsecs": 5}} + self.do_test(msg, "std_msgs/Time") + + msg = {"times": [{"secs": 3, "nsecs": 5}, {"secs": 2, "nsecs": 7}]} + self.do_test(msg, "rosbridge_library/TestTimeArray") + + def test_time_msg_now(self): + msg = {"data": "now"} + msgtype = "std_msgs/Time" + + inst = ros_loader.get_message_instance(msgtype) + c.populate_instance(msg, inst) + currenttime = rospy.get_rostime() + self.validate_instance(inst) + extracted = c.extract_values(inst) + print(extracted) + self.assertIn("data", extracted) + self.assertIn("secs", extracted["data"]) + self.assertIn("nsecs", extracted["data"]) + self.assertNotEqual(extracted["data"]["secs"], 0) + self.assertLessEqual(extracted["data"]["secs"], currenttime.secs) + self.assertGreaterEqual(currenttime.secs, extracted["data"]["secs"]) + + def test_duration_msg(self): + msg = {"data": {"secs": 3, "nsecs": 5}} + self.do_test(msg, "std_msgs/Duration") + + msg = {"durations": [{"secs": 3, "nsecs": 5}, {"secs": 2, "nsecs": 7}]} + self.do_test(msg, "rosbridge_library/TestDurationArray") + + def test_header_msg(self): + msg = {"seq": 5, "stamp": {"secs": 12347, "nsecs": 322304}, "frame_id": "2394dnfnlcx;v[p234j]"} + self.do_test(msg, "std_msgs/Header") + + msg = {"header": msg} + self.do_test(msg, "rosbridge_library/TestHeader") + self.do_test(msg, "rosbridge_library/TestHeaderTwo") + + msg = {"header": [msg["header"], msg["header"], msg["header"]]} + msg["header"][1]["seq"] = 6 + msg["header"][2]["seq"] = 7 + self.do_test(msg, "rosbridge_library/TestHeaderArray") + + def test_assorted_msgs(self): + assortedmsgs = ["geometry_msgs/Pose", "actionlib_msgs/GoalStatus", + "geometry_msgs/WrenchStamped", "stereo_msgs/DisparityImage", + "nav_msgs/OccupancyGrid", "geometry_msgs/Point32", "std_msgs/String", + "trajectory_msgs/JointTrajectoryPoint", "diagnostic_msgs/KeyValue", + "visualization_msgs/InteractiveMarkerUpdate", "nav_msgs/GridCells", + "sensor_msgs/PointCloud2"] + for rostype in assortedmsgs: + inst = ros_loader.get_message_instance(rostype) + msg = c.extract_values(inst) + self.do_test(msg, rostype) + l = loads(dumps(msg)) + inst2 = ros_loader.get_message_instance(rostype) + c.populate_instance(msg, inst2) + self.assertEqual(inst, inst2) + + def test_unexpected_key_in_dict_1(self): + rostype = "nav_msgs/GridCells" + inst = ros_loader.get_message_instance(rostype) + inst.cells = [ros_loader.get_message_instance("geometry_msgs/Point") for i in range(100)] + + msg = c.extract_values(inst) + self.do_test(msg, rostype) + msg_w_extra_key = msg + msg_w_extra_key["unexpected_key"] = "unexpected_val" + for i in range(100): + msg_w_extra_key["cells"][i]["unexpected_key"] = "unexpected_val" + + inst2 = ros_loader.get_message_instance(rostype) + c.populate_instance(msg_w_extra_key, inst2) + self.assertEqual(inst, inst2) + + def test_unexpected_key_in_dict_2(self): + rostype = "sensor_msgs/PointCloud2" + inst = ros_loader.get_message_instance(rostype) + inst.fields = [ros_loader.get_message_instance("sensor_msgs/PointField") for i in range(100)] + + msg = c.extract_values(inst) + self.do_test(msg, rostype) + msg_w_extra_key = msg + msg_w_extra_key["unexpected_key"] = "unexpected_val" + for i in range(100): + msg_w_extra_key["fields"][i]["unexpected_key"] = "unexpected_val" + + inst2 = ros_loader.get_message_instance(rostype) + c.populate_instance(msg_w_extra_key, inst2) + self.assertEqual(inst, inst2) + + def test_unexpected_key_in_dict_3(self): + rostype = "visualization_msgs/InteractiveMarkerUpdate" + inst = ros_loader.get_message_instance(rostype) + inst.markers = [ros_loader.get_message_instance("visualization_msgs/InteractiveMarker") for i in range(100)] + inst.poses = [ros_loader.get_message_instance("visualization_msgs/InteractiveMarkerPose") for i in range(100)] + + msg = c.extract_values(inst) + self.do_test(msg, rostype) + msg_w_extra_key = msg + msg_w_extra_key["unexpected_key"] = "unexpected_val" + for i in range(100): + msg_w_extra_key["markers"][i]["unexpected_key"] = "unexpected_val" + msg_w_extra_key["poses"][i]["unexpected_key"] = "unexpected_val" + + inst2 = ros_loader.get_message_instance(rostype) + c.populate_instance(msg_w_extra_key, inst2) + self.assertEqual(inst, inst2) + + def test_int8array(self): + def test_int8_msg(rostype, data): + msg = {"data": data} + inst = ros_loader.get_message_instance(rostype) + c.populate_instance(msg, inst) + self.validate_instance(inst) + return inst.data + + for msgtype in ["TestChar", "TestUInt8"]: + rostype = "rosbridge_library/" + msgtype + + int8s = list(range(0, 256)) + ret = test_int8_msg(rostype, int8s) + self.assertEqual(ret, bytes(bytearray(int8s))) + + str_int8s = bytes(bytearray(int8s)) + + b64str_int8s = standard_b64encode(str_int8s).decode('ascii') + ret = test_int8_msg(rostype, b64str_int8s) + self.assertEqual(ret, str_int8s) + + for msgtype in ["TestUInt8FixedSizeArray16"]: + rostype = "rosbridge_library/" + msgtype + + int8s = list(range(0, 16)) + ret = test_int8_msg(rostype, int8s) + self.assertEqual(ret, bytes(bytearray(int8s))) + + str_int8s = bytes(bytearray(int8s)) + + b64str_int8s = standard_b64encode(str_int8s).decode('ascii') + ret = test_int8_msg(rostype, b64str_int8s) + self.assertEqual(ret, str_int8s) + + +if __name__ == '__main__': + rosunit.unitrun(PKG, NAME, TestMessageConversion) From 986a532418e0d1bd05878a8b5d90b7af4f704328 Mon Sep 17 00:00:00 2001 From: imoted Date: Tue, 26 Jul 2022 18:09:41 +0900 Subject: [PATCH 06/10] remove python2 support --- ros_awsiot_agent/test/test_message_conversion.py | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/ros_awsiot_agent/test/test_message_conversion.py b/ros_awsiot_agent/test/test_message_conversion.py index 32e509c..314c162 100755 --- a/ros_awsiot_agent/test/test_message_conversion.py +++ b/ros_awsiot_agent/test/test_message_conversion.py @@ -5,12 +5,7 @@ import rosunit import unittest from json import loads, dumps - -try: - from cStringIO import StringIO # Python 2.x -except ImportError: - from io import BytesIO as StringIO # Python 3.x - +from io import BytesIO as StringIO from src.ros_awsiot_agent import message_conversion as c from rosbridge_library.internal import ros_loader From b6a264d0dddc4ccce8d24e32ee9a3a66e5982bbd Mon Sep 17 00:00:00 2001 From: imoted Date: Tue, 26 Jul 2022 18:09:59 +0900 Subject: [PATCH 07/10] add the test launch file --- ros_awsiot_agent/launch/mqtt_ros.launch | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) create mode 100644 ros_awsiot_agent/launch/mqtt_ros.launch diff --git a/ros_awsiot_agent/launch/mqtt_ros.launch b/ros_awsiot_agent/launch/mqtt_ros.launch new file mode 100644 index 0000000..76d52a3 --- /dev/null +++ b/ros_awsiot_agent/launch/mqtt_ros.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + From 38056c8df28b6679fbce7e2b2e04c3e4e27aa25a Mon Sep 17 00:00:00 2001 From: imoted Date: Tue, 26 Jul 2022 18:12:25 +0900 Subject: [PATCH 08/10] fix the flake8 alert --- ros_awsiot_agent/test/test_message_conversion.py | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ros_awsiot_agent/test/test_message_conversion.py b/ros_awsiot_agent/test/test_message_conversion.py index 314c162..8fcc3a5 100755 --- a/ros_awsiot_agent/test/test_message_conversion.py +++ b/ros_awsiot_agent/test/test_message_conversion.py @@ -9,7 +9,7 @@ from src.ros_awsiot_agent import message_conversion as c from rosbridge_library.internal import ros_loader -from base64 import standard_b64encode, standard_b64decode +from base64 import standard_b64encode if sys.version_info >= (3, 0): string_types = (str,) @@ -238,7 +238,6 @@ def test_assorted_msgs(self): inst = ros_loader.get_message_instance(rostype) msg = c.extract_values(inst) self.do_test(msg, rostype) - l = loads(dumps(msg)) inst2 = ros_loader.get_message_instance(rostype) c.populate_instance(msg, inst2) self.assertEqual(inst, inst2) From 53d891dcbd5e507167d2a036f2ed3694a8ece0ea Mon Sep 17 00:00:00 2001 From: imoted Date: Wed, 27 Jul 2022 14:47:42 +0900 Subject: [PATCH 09/10] =?UTF-8?q?=E5=86=97=E9=95=B7=E3=81=AA=E3=83=86?= =?UTF-8?q?=E3=82=B9=E3=83=88=E3=82=92=E5=89=8A=E9=99=A4=E3=80=81=E6=96=B0?= =?UTF-8?q?=E3=81=9F=E3=81=AB=E8=BE=9E=E6=9B=B8=E5=86=85=E8=BE=9E=E6=9B=B8?= =?UTF-8?q?=E3=81=AE=E6=A7=8B=E9=80=A0=E3=81=AE=E3=83=86=E3=82=B9=E3=83=88?= =?UTF-8?q?=E3=82=92=E8=BF=BD=E5=8A=A0?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../test/test_message_conversion.py | 33 ++++++++----------- 1 file changed, 13 insertions(+), 20 deletions(-) diff --git a/ros_awsiot_agent/test/test_message_conversion.py b/ros_awsiot_agent/test/test_message_conversion.py index 8fcc3a5..8e7e380 100755 --- a/ros_awsiot_agent/test/test_message_conversion.py +++ b/ros_awsiot_agent/test/test_message_conversion.py @@ -242,39 +242,34 @@ def test_assorted_msgs(self): c.populate_instance(msg, inst2) self.assertEqual(inst, inst2) - def test_unexpected_key_in_dict_1(self): + def test_unexpected_key_in_dict1(self): rostype = "nav_msgs/GridCells" inst = ros_loader.get_message_instance(rostype) inst.cells = [ros_loader.get_message_instance("geometry_msgs/Point") for i in range(100)] msg = c.extract_values(inst) self.do_test(msg, rostype) - msg_w_extra_key = msg - msg_w_extra_key["unexpected_key"] = "unexpected_val" - for i in range(100): - msg_w_extra_key["cells"][i]["unexpected_key"] = "unexpected_val" + msg["unexpected_key"] = "unexpected_val" inst2 = ros_loader.get_message_instance(rostype) - c.populate_instance(msg_w_extra_key, inst2) + c.populate_instance(msg, inst2) self.assertEqual(inst, inst2) - def test_unexpected_key_in_dict_2(self): - rostype = "sensor_msgs/PointCloud2" + def test_unexpected_key_in_dict2(self): + rostype = "nav_msgs/GridCells" inst = ros_loader.get_message_instance(rostype) - inst.fields = [ros_loader.get_message_instance("sensor_msgs/PointField") for i in range(100)] + inst.cells = [ros_loader.get_message_instance("geometry_msgs/Point") for i in range(100)] msg = c.extract_values(inst) self.do_test(msg, rostype) - msg_w_extra_key = msg - msg_w_extra_key["unexpected_key"] = "unexpected_val" - for i in range(100): - msg_w_extra_key["fields"][i]["unexpected_key"] = "unexpected_val" + msg["unexpected_key"] = dict() + msg["unexpected_key"]["unexpected_key"] = "unexpected_val" inst2 = ros_loader.get_message_instance(rostype) - c.populate_instance(msg_w_extra_key, inst2) + c.populate_instance(msg, inst2) self.assertEqual(inst, inst2) - def test_unexpected_key_in_dict_3(self): + def test_unexpected_key_in_list_in_dict(self): rostype = "visualization_msgs/InteractiveMarkerUpdate" inst = ros_loader.get_message_instance(rostype) inst.markers = [ros_loader.get_message_instance("visualization_msgs/InteractiveMarker") for i in range(100)] @@ -282,14 +277,12 @@ def test_unexpected_key_in_dict_3(self): msg = c.extract_values(inst) self.do_test(msg, rostype) - msg_w_extra_key = msg - msg_w_extra_key["unexpected_key"] = "unexpected_val" for i in range(100): - msg_w_extra_key["markers"][i]["unexpected_key"] = "unexpected_val" - msg_w_extra_key["poses"][i]["unexpected_key"] = "unexpected_val" + msg["markers"][i]["unexpected_key"] = "unexpected_val" + msg["poses"][i]["unexpected_key"] = "unexpected_val" inst2 = ros_loader.get_message_instance(rostype) - c.populate_instance(msg_w_extra_key, inst2) + c.populate_instance(msg, inst2) self.assertEqual(inst, inst2) def test_int8array(self): From bf3e2ef4179c92a271ff10df46704cf4b2cae2e1 Mon Sep 17 00:00:00 2001 From: imoted Date: Wed, 27 Jul 2022 14:55:45 +0900 Subject: [PATCH 10/10] =?UTF-8?q?=E5=AE=9F=E9=9A=9B=E3=81=AEROS=20msg?= =?UTF-8?q?=E3=81=AE=E5=BD=A2=E5=BC=8F=E3=81=A7=E8=BE=9E=E6=9B=B8=E5=86=85?= =?UTF-8?q?=E3=80=81=E8=BE=9E=E6=9B=B8=E3=81=AB=E4=BD=99=E5=88=86=E3=81=AA?= =?UTF-8?q?key=E3=81=8C=E3=81=82=E3=81=A3=E3=81=9F=E9=9A=9B=E3=81=AE?= =?UTF-8?q?=E3=80=81=E3=83=86=E3=82=B9=E3=83=88=E3=81=AB=E5=A4=89=E6=9B=B4?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ros_awsiot_agent/test/test_message_conversion.py | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/ros_awsiot_agent/test/test_message_conversion.py b/ros_awsiot_agent/test/test_message_conversion.py index 8e7e380..b2bec02 100755 --- a/ros_awsiot_agent/test/test_message_conversion.py +++ b/ros_awsiot_agent/test/test_message_conversion.py @@ -256,14 +256,12 @@ def test_unexpected_key_in_dict1(self): self.assertEqual(inst, inst2) def test_unexpected_key_in_dict2(self): - rostype = "nav_msgs/GridCells" + rostype = "actionlib_msgs/GoalStatus" inst = ros_loader.get_message_instance(rostype) - inst.cells = [ros_loader.get_message_instance("geometry_msgs/Point") for i in range(100)] msg = c.extract_values(inst) self.do_test(msg, rostype) - msg["unexpected_key"] = dict() - msg["unexpected_key"]["unexpected_key"] = "unexpected_val" + msg["goal_id"]["unexpected_key"] = "unexpected_val" inst2 = ros_loader.get_message_instance(rostype) c.populate_instance(msg, inst2)