From 5e87ee8de6e9f9f4a772a66f4ae0ec5db6120144 Mon Sep 17 00:00:00 2001 From: Jacob Bandes-Storch Date: Tue, 16 Aug 2022 11:51:49 -0700 Subject: [PATCH] Allow integers in conversion to float array messages (#777) Fixes https://github.com/RobotWebTools/rosbridge_suite/issues/764 by using `ndarray`/`array` assignment operations that accept ints as well as floats, rather than directly assigning the incoming list value, which failed at the msg/idl generated python code's validation step. --- .../rosbridge_library/internal/message_conversion.py | 9 +++++++-- .../test/internal/test_message_conversion.py | 10 ++++++++++ 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/rosbridge_library/src/rosbridge_library/internal/message_conversion.py b/rosbridge_library/src/rosbridge_library/internal/message_conversion.py index 72ce62299..df46b5574 100644 --- a/rosbridge_library/src/rosbridge_library/internal/message_conversion.py +++ b/rosbridge_library/src/rosbridge_library/internal/message_conversion.py @@ -358,8 +358,13 @@ def _to_list_inst(msg, rostype, roottype, inst, stack): return [] # Special mappings for numeric types https://design.ros2.org/articles/idl_interface_definition.html - if isinstance(inst, array.array) or isinstance(inst, np.ndarray): - return msg + if isinstance(inst, array.array): + del inst[:] + inst.extend(msg) # accepts both ints and floats which may come from json + return inst + if isinstance(inst, np.ndarray): + inst[:] = msg # accepts both ints and floats which may come from json + return inst # Remove the list indicators from the rostype try: diff --git a/rosbridge_library/test/internal/test_message_conversion.py b/rosbridge_library/test/internal/test_message_conversion.py index d75313dc2..9ccba4f05 100755 --- a/rosbridge_library/test/internal/test_message_conversion.py +++ b/rosbridge_library/test/internal/test_message_conversion.py @@ -299,6 +299,11 @@ def test_float32_msg(rostype, data): ret = test_float32_msg(rostype, floats) np.testing.assert_array_equal(ret, np.array(floats)) + # From List[int] + ints = list(map(int, range(0, 256))) + ret = test_float32_msg(rostype, ints) + np.testing.assert_array_equal(ret, np.array(ints)) + for msgtype in ["TestFloat32BoundedArray"]: rostype = "rosbridge_test_msgs/" + msgtype @@ -306,3 +311,8 @@ def test_float32_msg(rostype, data): floats = list(map(float, range(0, 16))) ret = test_float32_msg(rostype, floats) np.testing.assert_array_equal(ret, np.array(floats)) + + # From List[int] + ints = list(map(int, range(0, 16))) + ret = test_float32_msg(rostype, ints) + np.testing.assert_array_equal(ret, np.array(ints))