Skip to content

Commit

Permalink
Fixes for Python 3 compatibility. (#978, #565)
Browse files Browse the repository at this point in the history
* tcpros_service.py: encode error messages as bytes in python3 before packing them.

* test_rospy_tcpros_base.py: check against bytes equality for python3 compatibility.

* test_rospy_tcpros_pubsub.py: use bytes data instead of str for python3 compatibility.

* test_rospy_topics.py: check for bytes equality for python3 compatibility

* test_rosservice_command_line_online.py: pipes are bytes with python3, compare or decode accordingly. Fixes this test with python3.

* test_bag.py: use range() instead of xrange() so that it works with python 2 & 3. Since it is a test, performance does not matter much.
  • Loading branch information
aballier authored and mikepurvis committed Feb 9, 2017
1 parent 544a848 commit 7921cde
Show file tree
Hide file tree
Showing 6 changed files with 19 additions and 17 deletions.
2 changes: 2 additions & 0 deletions clients/rospy/src/rospy/impl/tcpros_service.py
Original file line number Diff line number Diff line change
Expand Up @@ -608,6 +608,8 @@ def _write_service_error(self, transport, err_msg):
@param err_msg: error message to send to client
@type err_msg: str
"""
if sys.hexversion > 0x03000000: #Python3
err_msg = bytes(err_msg, 'utf-8')
transport.write_data(struct.pack('<BI%ss'%len(err_msg), 0, len(err_msg), err_msg))

def _handle_request(self, transport, request):
Expand Down
10 changes: 5 additions & 5 deletions test/test_rosbag/test/test_bag.py
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,7 @@ def test_future_version_works(self):
def test_get_message_count(self):
fn = '/tmp/test_get_message_count.bag'
with rosbag.Bag(fn, mode='w') as bag:
for i in xrange(100):
for i in range(100):
bag.write("/test_bag", Int32(data=i))
bag.write("/test_bag", String(data='also'))
bag.write("/test_bag/more", String(data='alone'))
Expand All @@ -303,7 +303,7 @@ def test_get_compression_info(self):

# No Compression
with rosbag.Bag(fn, mode='w') as bag:
for i in xrange(100):
for i in range(100):
bag.write("/test_bag", Int32(data=i))

with rosbag.Bag(fn) as bag:
Expand All @@ -314,7 +314,7 @@ def test_get_compression_info(self):
self.assertEquals(info.compressed, 5166)

with rosbag.Bag(fn, mode='w', compression=rosbag.Compression.BZ2) as bag:
for i in xrange(100):
for i in range(100):
bag.write("/test_bag", Int32(data=i))

with rosbag.Bag(fn) as bag:
Expand All @@ -331,7 +331,7 @@ def test_get_time(self):
fn = '/tmp/test_get_time.bag'

with rosbag.Bag(fn, mode='w') as bag:
for i in xrange(100):
for i in range(100):
bag.write("/test_bag", Int32(data=i), t=genpy.Time.from_sec(i))

with rosbag.Bag(fn) as bag:
Expand All @@ -358,7 +358,7 @@ def test_get_type_and_topic_info(self):
topic_1 = "/test_bag"
topic_2 = "/test_bag/more"
with rosbag.Bag(fn, mode='w') as bag:
for i in xrange(100):
for i in range(100):
bag.write(topic_1, Int32(data=i))
bag.write(topic_1, String(data='also'))
bag.write(topic_2, String(data='alone'))
Expand Down
4 changes: 2 additions & 2 deletions test/test_rospy/test/unit/test_rospy_tcpros_base.py
Original file line number Diff line number Diff line change
Expand Up @@ -154,8 +154,8 @@ def test_TCPROSTransport(self):
self.assertEquals('TCPROS', t.transport_type)
self.assertEquals(OUTBOUND, t.direction)
self.assertEquals('unknown', t.endpoint_id)
self.assertEquals('', t.read_buff.getvalue())
self.assertEquals('', t.write_buff.getvalue())
self.assertEquals(b'', t.read_buff.getvalue())
self.assertEquals(b'', t.write_buff.getvalue())

s = MockSock('12345')
t.set_socket(s, 'new_endpoint_id')
Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/test/unit/test_rospy_tcpros_pubsub.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@

class FakeSocket(object):
def __init__(self):
self.data = ''
self.data = b''
self.sockopt = None
def fileno(self):
# fool select logic by giving it stdout fileno
Expand Down
2 changes: 1 addition & 1 deletion test/test_rospy/test/unit/test_rospy_topics.py
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ def test_Publisher(self):
self.assertEquals(None, impl.latch)
self.assertEquals(0, impl.seq)
self.assertEquals(1, impl.ref_count)
self.assertEquals('', impl.buff.getvalue())
self.assertEquals(b'', impl.buff.getvalue())
self.failIf(impl.closed)
self.failIf(impl.has_connections())
# check publish() fall-through
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,28 +88,28 @@ def test_rosservice(self):
for name in names:
# args
output = Popen([cmd, 'args', name], stdout=PIPE).communicate()[0]
self.assertEquals('a b', output.strip())
self.assertEquals(b'a b', output.strip())

# type
output = Popen([cmd, 'type', name], stdout=PIPE).communicate()[0]
self.assertEquals('test_rosmaster/AddTwoInts', output.strip())
self.assertEquals(b'test_rosmaster/AddTwoInts', output.strip())

# find
output = Popen([cmd, 'find', 'test_rosmaster/AddTwoInts'], stdout=PIPE).communicate()[0]
values = [v.strip() for v in output.split('\n') if v.strip()]
values = [v.strip() for v in output.decode().split('\n') if v.strip()]
self.assertEquals(set(values), set(services))

# uri
output = Popen([cmd, 'uri', name], stdout=PIPE).communicate()[0]
# - no exact answer
self.assert_(output.startswith('rosrpc://'), output)
self.assert_(output.decode().startswith('rosrpc://'), output)

# call
output = Popen([cmd, 'call', '--wait', name, '1', '2'], stdout=PIPE).communicate()[0]
self.assertEquals('sum: 3', output.strip())
self.assertEquals(b'sum: 3', output.strip())

output = Popen([cmd, 'call', name, '1', '2'], stdout=PIPE).communicate()[0]
self.assertEquals('sum: 3', output.strip())
self.assertEquals(b'sum: 3', output.strip())

name = 'header_echo'
# test with a Header so we can validate keyword args
Expand Down Expand Up @@ -143,13 +143,13 @@ def test_rosservice(self):
env['ROS_NAMESPACE'] = 'foo'
uri1 = Popen([cmd, 'uri', 'add_two_ints'], stdout=PIPE).communicate()[0]
uri2 = Popen([cmd, 'uri', 'add_two_ints'], env=env, stdout=PIPE).communicate()[0]
self.assert_(uri2.startswith('rosrpc://'))
self.assert_(uri2.decode().startswith('rosrpc://'))
self.assertNotEquals(uri1, uri2)

# test_call_wait
def task1():
output = Popen([cmd, 'call', '--wait', 'wait_two_ints', '1', '2'], stdout=PIPE).communicate()[0]
self.assertEquals('sum: 3', output.strip())
self.assertEquals(b'sum: 3', output.strip())
timeout_t = time.time() + 5.
t1 = TestTask(task1)
t1.start()
Expand Down

0 comments on commit 7921cde

Please sign in to comment.