Skip to content

Commit

Permalink
more Python 3 compatibility (#1796)
Browse files Browse the repository at this point in the history
* keep subscribers around

* more subprocess decode

* add another seek(0), remove an unncessary one
  • Loading branch information
dirk-thomas authored Aug 19, 2019
1 parent 7671747 commit d487d58
Show file tree
Hide file tree
Showing 4 changed files with 6 additions and 6 deletions.
2 changes: 1 addition & 1 deletion test/test_rospy/nodes/listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/test/rostest/test_topic_statistics.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/test/unit/test_rospy_msg.py
Original file line number Diff line number Diff line change
Expand Up @@ -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))
Expand All @@ -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)
Expand Down
6 changes: 3 additions & 3 deletions utilities/roswtf/test/check_roswtf_command_line_online.py
Original file line number Diff line number Diff line change
Expand Up @@ -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):
Expand Down Expand Up @@ -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):
Expand Down

0 comments on commit d487d58

Please sign in to comment.