From d487d5877049d61fe2ebcc6487e9a7a72d9f0346 Mon Sep 17 00:00:00 2001 From: Dirk Thomas Date: Mon, 19 Aug 2019 08:56:50 -0700 Subject: [PATCH] more Python 3 compatibility (#1796) * keep subscribers around * more subprocess decode * add another seek(0), remove an unncessary one --- test/test_rospy/nodes/listener.py | 2 +- test/test_rospy/test/rostest/test_topic_statistics.py | 2 +- test/test_rospy/test/unit/test_rospy_msg.py | 2 +- utilities/roswtf/test/check_roswtf_command_line_online.py | 6 +++--- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/test/test_rospy/nodes/listener.py b/test/test_rospy/nodes/listener.py index dc2aa736ed..c8629523a9 100755 --- a/test/test_rospy/nodes/listener.py +++ b/test/test_rospy/nodes/listener.py @@ -55,7 +55,7 @@ def listener(): # run simultaenously. rospy.init_node('listener', anonymous=True) - rospy.Subscriber("chatter", String, callback) + sub = rospy.Subscriber("chatter", String, callback) # spin() simply keeps python from exiting until this node is stopped rospy.spin() diff --git a/test/test_rospy/test/rostest/test_topic_statistics.py b/test/test_rospy/test/rostest/test_topic_statistics.py index d7642725ed..ead3bd5edb 100755 --- a/test/test_rospy/test/rostest/test_topic_statistics.py +++ b/test/test_rospy/test/rostest/test_topic_statistics.py @@ -74,7 +74,7 @@ def frequency_acceptable(self, topic, expected, error_margin=0.1): return abs(found_freq - expected) / expected <= error_margin def test_frequencies(self): - rospy.Subscriber('/statistics', TopicStatistics, self.new_msg) + sub = rospy.Subscriber('/statistics', TopicStatistics, self.new_msg) self.assert_eventually( lambda: '/very_fast_chatter' in self.topic_statistic_msg_map) diff --git a/test/test_rospy/test/unit/test_rospy_msg.py b/test/test_rospy/test/unit/test_rospy_msg.py index beee381429..e130ba44f0 100644 --- a/test/test_rospy/test/unit/test_rospy_msg.py +++ b/test/test_rospy/test/unit/test_rospy_msg.py @@ -199,6 +199,7 @@ def validate_vals(vals, teststrs=teststrs): #deserialize with extra data leftover b.truncate(0) + b.seek(0) b.write(valids[0]+b'leftovers') rospy.msg.deserialize_messages(b, msg_queue, data_class) self.assertEquals(1, len(msg_queue)) @@ -224,7 +225,6 @@ def validate_vals(vals, teststrs=teststrs): #deserialize multiple values with max_msgs max_msgs = 5 b.truncate(0) - b.seek(0) for v in valids: b.write(v) rospy.msg.deserialize_messages(b, msg_queue, data_class, max_msgs=max_msgs) diff --git a/utilities/roswtf/test/check_roswtf_command_line_online.py b/utilities/roswtf/test/check_roswtf_command_line_online.py index 7a0cfa54d2..75c0bcc7f4 100755 --- a/utilities/roswtf/test/check_roswtf_command_line_online.py +++ b/utilities/roswtf/test/check_roswtf_command_line_online.py @@ -64,7 +64,7 @@ def setUp(self): ## test that the rosmsg command works def test_cmd_help(self): cmd = 'roswtf' - output = Popen([cmd, '-h'], stdout=PIPE).communicate()[0] + output = Popen([cmd, '-h'], stdout=PIPE).communicate()[0].decode() self.assert_('Options' in output) def test_offline(self): @@ -117,12 +117,12 @@ def test_offline(self): # every package in the ROS stack, which doesn't work. output, err = Popen([cmd], **kwds).communicate() - self._check_output([cmd], output, err) + self._check_output([cmd], output.decode(), err.decode()) # run roswtf on a simple launch file online rospack = rospkg.RosPack() p = os.path.join(rospack.get_path('roswtf'), 'test', 'min.launch') - output = Popen([cmd, p], **kwds).communicate()[0] + output = Popen([cmd, p], **kwds).communicate()[0].decode() self._check_output([cmd, p], output) def _check_output(self, cmd, output, error=None):