Skip to content

Commit c14cc88

Browse files
authored
Merge pull request #4 from fmessmer/test_noetic
test noetic
2 parents ea7c46e + 0c2ba90 commit c14cc88

8 files changed

+75
-75
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
# CMake
33
##############################################################################
44

5-
cmake_minimum_required(VERSION 2.8.3)
5+
cmake_minimum_required(VERSION 3.0.2)
66
project(rosjava_core)
77

88
##############################################################################

rosjava/test/test_composite_passthrough.py

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -67,37 +67,37 @@ def cb_from_test(self, msg):
6767
def test_composite_passthrough(self):
6868
# 20 seconds to validate fixture
6969
timeout_t = time.time() + 20.
70-
print "waiting for 20 seconds for fixture to verify"
70+
print("waiting for 20 seconds for fixture to verify")
7171
while self.fixture_curr is None and \
7272
not rospy.is_shutdown() and \
7373
timeout_t > time.time():
7474
time.sleep(0.2)
7575

76-
self.failIf(timeout_t < time.time(), "timeout exceeded")
77-
self.failIf(rospy.is_shutdown(), "node shutdown")
78-
self.failIf(self.fixture_curr is None, "no data from fixture")
76+
self.assertFalse(timeout_t < time.time(), "timeout exceeded")
77+
self.assertFalse(rospy.is_shutdown(), "node shutdown")
78+
self.assertFalse(self.fixture_curr is None, "no data from fixture")
7979
m = self.fixture_curr
80-
self.assertAlmostEquals(m.a.x, m.b.x)
81-
self.assertAlmostEquals(m.a.y, m.b.y)
82-
self.assertAlmostEquals(m.a.z, m.b.z)
80+
self.assertAlmostEqual(m.a.x, m.b.x)
81+
self.assertAlmostEqual(m.a.y, m.b.y)
82+
self.assertAlmostEqual(m.a.z, m.b.z)
8383

8484
# another 20 seconds to validate client
8585
timeout_t = time.time() + 20.
86-
print "waiting for 20 seconds for client to verify"
86+
print("waiting for 20 seconds for client to verify")
8787
while self.test_curr is None and \
8888
not rospy.is_shutdown() and \
8989
timeout_t > time.time():
9090
time.sleep(0.2)
9191

92-
self.failIf(self.test_curr is None, "no data from test")
92+
self.assertFalse(self.test_curr is None, "no data from test")
9393
m = self.test_curr
94-
self.assertAlmostEquals(m.a.x, m.b.x)
95-
self.assertAlmostEquals(m.a.y, m.b.y)
96-
self.assertAlmostEquals(m.a.z, m.b.z)
94+
self.assertAlmostEqual(m.a.x, m.b.x)
95+
self.assertAlmostEqual(m.a.y, m.b.y)
96+
self.assertAlmostEqual(m.a.z, m.b.z)
9797

9898
# a.w = a.x + a.y + a.z. Just make sure we're in the ballpark
9999
a = self.test_curr.a
100-
self.assert_(abs(a.x + a.y + a.z - a.w) < 10.)
100+
self.assertTrue(abs(a.x + a.y + a.z - a.w) < 10.)
101101

102102
if __name__ == '__main__':
103103
import rostest

rosjava/test/test_int64_passthrough.py

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -70,28 +70,28 @@ def cb_from_test(self, msg):
7070
def test_int64_passthrough(self):
7171
# 20 seconds to validate fixture
7272
timeout_t = time.time() + 20.
73-
print "waiting for 20 seconds for fixture to verify"
73+
print("waiting for 20 seconds for fixture to verify")
7474
while self.fixture_prev is None and \
7575
not rospy.is_shutdown() and \
7676
timeout_t > time.time():
7777
time.sleep(0.2)
7878

79-
self.failIf(timeout_t < time.time(), "timeout exceeded")
80-
self.failIf(rospy.is_shutdown(), "node shutdown")
81-
self.failIf(self.fixture_prev is None, "no data from fixture")
82-
self.failIf(self.fixture_curr is None, "no data from fixture")
83-
self.assertEquals(self.fixture_prev.data + 1, self.fixture_curr.data, "fixture should incr by one")
79+
self.assertFalse(timeout_t < time.time(), "timeout exceeded")
80+
self.assertFalse(rospy.is_shutdown(), "node shutdown")
81+
self.assertFalse(self.fixture_prev is None, "no data from fixture")
82+
self.assertFalse(self.fixture_curr is None, "no data from fixture")
83+
self.assertEqual(self.fixture_prev.data + 1, self.fixture_curr.data, "fixture should incr by one")
8484

8585
# another 20 seconds to validate client
8686
timeout_t = time.time() + 20.
87-
print "waiting for 20 seconds for client to verify"
87+
print("waiting for 20 seconds for client to verify")
8888
while self.test_prev is None and \
8989
not rospy.is_shutdown() and \
9090
timeout_t > time.time():
9191
time.sleep(0.2)
9292

93-
self.failIf(self.test_prev is None, "no data from test")
94-
self.assertEquals(self.test_prev.data + 1, self.test_curr.data, "test does not appear to match fixture data")
93+
self.assertFalse(self.test_prev is None, "no data from test")
94+
self.assertEqual(self.test_prev.data + 1, self.test_curr.data, "test does not appear to match fixture data")
9595

9696

9797
if __name__ == '__main__':

rosjava/test/test_parameter_client.py

Lines changed: 26 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,7 @@ def tilde_cb(self, msg):
8585

8686
def test_parameter_client_read(self):
8787
timeout_t = time.time() + 20.
88-
print "waiting for 20 seconds for client to load"
88+
print("waiting for 20 seconds for client to load")
8989

9090
tests = self.tests
9191
msgs = [None]
@@ -95,36 +95,36 @@ def test_parameter_client_read(self):
9595
time.sleep(0.2)
9696
msgs = [getattr(self, t+'_msg') for t in tests]
9797

98-
print "msgs: %s"%(msgs)
98+
print("msgs: %s"%(msgs))
9999

100-
self.failIf(timeout_t < time.time(), "timeout exceeded")
101-
self.failIf(rospy.is_shutdown(), "node shutdown")
102-
self.failIf(any(1 for m in msgs if m is None), "did not receive all expected messages: "+str(msgs))
100+
self.assertFalse(timeout_t < time.time(), "timeout exceeded")
101+
self.assertFalse(rospy.is_shutdown(), "node shutdown")
102+
self.assertFalse(any(1 for m in msgs if m is None), "did not receive all expected messages: "+str(msgs))
103103

104104
ns = rospy.get_param('parameter_namespace')
105105
for t in tests:
106106
p_name = roslib.names.ns_join(ns, t)
107107
value = rospy.get_param(p_name, t)
108108
msg = getattr(self, "%s_msg"%(t))
109-
print "get param: %s"%(p_name)
110-
print "param value: %s"%(value)
111-
print "msg value: %s"%(msg)
109+
print("get param: %s"%(p_name))
110+
print("param value: %s"%(value))
111+
print("msg value: %s"%(msg))
112112
if t == 'composite':
113-
print "value", p_name, value
113+
print("value", p_name, value)
114114
m = Composite(CompositeA(**value['a']), CompositeB(**value['b']))
115-
self.assertAlmostEquals(m.a.x, msg.a.x)
116-
self.assertAlmostEquals(m.a.y, msg.a.y)
117-
self.assertAlmostEquals(m.a.z, msg.a.z)
118-
self.assertAlmostEquals(m.a.w, msg.a.w)
119-
self.assertAlmostEquals(m.b.x, msg.b.x)
120-
self.assertAlmostEquals(m.b.y, msg.b.y)
121-
self.assertAlmostEquals(m.b.z, msg.b.z)
115+
self.assertAlmostEqual(m.a.x, msg.a.x)
116+
self.assertAlmostEqual(m.a.y, msg.a.y)
117+
self.assertAlmostEqual(m.a.z, msg.a.z)
118+
self.assertAlmostEqual(m.a.w, msg.a.w)
119+
self.assertAlmostEqual(m.b.x, msg.b.x)
120+
self.assertAlmostEqual(m.b.y, msg.b.y)
121+
self.assertAlmostEqual(m.b.z, msg.b.z)
122122
elif t == 'list':
123-
self.assertEquals(list(value), list(msg.int32_array))
123+
self.assertEqual(list(value), list(msg.int32_array))
124124
elif t == 'float':
125-
self.assertAlmostEquals(value, msg.data)
125+
self.assertAlmostEqual(value, msg.data)
126126
else:
127-
self.assertEquals(value, msg.data)
127+
self.assertEqual(value, msg.data)
128128

129129
def test_set_parameter(self):
130130
# make sure client copied each parameter correct
@@ -137,23 +137,23 @@ def test_set_parameter(self):
137137
source_value = rospy.get_param(source_name)
138138
target_value = rospy.get_param(target_name)
139139
if t != 'float':
140-
self.assertEquals(source_value, target_value)
140+
self.assertEqual(source_value, target_value)
141141
else:
142-
self.assertAlmostEquals(source_value, target_value)
142+
self.assertAlmostEqual(source_value, target_value)
143143

144144
def test_tilde_parameter(self):
145145
timeout_t = time.time() + 20.
146-
print "waiting for 20 seconds for client to load"
146+
print("waiting for 20 seconds for client to load")
147147
while self.tilde_msg is None and \
148148
not rospy.is_shutdown() and \
149149
timeout_t > time.time():
150150
time.sleep(0.2)
151151

152-
self.failIf(timeout_t < time.time(), "timeout exceeded")
153-
self.failIf(rospy.is_shutdown(), "node shutdown")
154-
self.failIf(self.tilde_msg is None)
152+
self.assertFalse(timeout_t < time.time(), "timeout exceeded")
153+
self.assertFalse(rospy.is_shutdown(), "node shutdown")
154+
self.assertFalse(self.tilde_msg is None)
155155

156-
self.assertEquals(rospy.get_param('param_client/tilde'), self.tilde_msg.data)
156+
self.assertEqual(rospy.get_param('param_client/tilde'), self.tilde_msg.data)
157157

158158
if __name__ == '__main__':
159159
import rostest

rosjava/test/test_string_passthrough.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ class TestStringPassthrough(unittest.TestCase):
5151

5252
def setUp(self):
5353
rospy.init_node(NAME)
54-
self.nodes = ['/node%s'%(i) for i in xrange(10)]
54+
self.nodes = ['/node%s'%(i) for i in range(10)]
5555
self.nodes_set = set(self.nodes)
5656

5757
# keep track of nodes that have done callbacks
@@ -70,31 +70,31 @@ def cb_from_test(self, msg):
7070
def test_string_passthrough(self):
7171
# 20 seconds to validate fixture
7272
timeout_t = time.time() + 20.
73-
print "waiting for 20 seconds for fixture to verify"
73+
print("waiting for 20 seconds for fixture to verify")
7474
while not self.fixture_nodes_cb == self.nodes_set and \
7575
not rospy.is_shutdown() and \
7676
timeout_t > time.time():
7777
time.sleep(0.2)
7878

79-
self.failIf(timeout_t < time.time(), "timeout exceeded")
80-
self.failIf(rospy.is_shutdown(), "node shutdown")
81-
self.assertEquals(self.nodes_set, self.fixture_nodes_cb, "fixture did not validate: %s vs %s"%(self.nodes_set, self.fixture_nodes_cb))
79+
self.assertFalse(timeout_t < time.time(), "timeout exceeded")
80+
self.assertFalse(rospy.is_shutdown(), "node shutdown")
81+
self.assertEqual(self.nodes_set, self.fixture_nodes_cb, "fixture did not validate: %s vs %s"%(self.nodes_set, self.fixture_nodes_cb))
8282

8383
# another 20 seconds to validate client
8484
timeout_t = time.time() + 20.
85-
print "waiting for 20 seconds for client to verify"
85+
print("waiting for 20 seconds for client to verify")
8686
while not self.test_nodes_cb == self.nodes_set and \
8787
not rospy.is_shutdown() and \
8888
timeout_t > time.time():
8989
time.sleep(0.2)
9090

91-
self.assertEquals(self.nodes_set, self.test_nodes_cb, "passthrough did not pass along all message")
91+
self.assertEqual(self.nodes_set, self.test_nodes_cb, "passthrough did not pass along all message")
9292

9393
# Create a new Publisher here. This will validate publisherUpdate()
9494
pub = rospy.Publisher('string_in', String)
9595
msg = 'test_publisherUpdate'
9696
timeout_t = time.time() + 20.
97-
print "waiting for 20 seconds for client to verify"
97+
print("waiting for 20 seconds for client to verify")
9898
while not msg in self.nodes_set and \
9999
not rospy.is_shutdown() and \
100100
timeout_t > time.time():

rosjava/test/test_testheader_passthrough.py

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -67,32 +67,32 @@ def cb_from_test(self, msg):
6767
def test_testheader_passthrough(self):
6868
# 20 seconds to validate fixture
6969
timeout_t = time.time() + 20.
70-
print "waiting for 20 seconds for fixture to verify"
70+
print("waiting for 20 seconds for fixture to verify")
7171
while self.fixture_curr is None and \
7272
not rospy.is_shutdown() and \
7373
timeout_t > time.time():
7474
time.sleep(0.2)
7575

76-
self.failIf(timeout_t < time.time(), "timeout exceeded")
77-
self.failIf(rospy.is_shutdown(), "node shutdown")
78-
self.failIf(self.fixture_curr is None, "no data from fixture")
79-
self.assertEquals('/node0', self.fixture_curr.caller_id)
80-
self.assertEquals('', self.fixture_curr.orig_caller_id)
76+
self.assertFalse(timeout_t < time.time(), "timeout exceeded")
77+
self.assertFalse(rospy.is_shutdown(), "node shutdown")
78+
self.assertFalse(self.fixture_curr is None, "no data from fixture")
79+
self.assertEqual('/node0', self.fixture_curr.caller_id)
80+
self.assertEqual('', self.fixture_curr.orig_caller_id)
8181

8282
# another 20 seconds to validate client
8383
timeout_t = time.time() + 20.
84-
print "waiting for 20 seconds for client to verify"
84+
print("waiting for 20 seconds for client to verify")
8585
while self.test_curr is None and \
8686
not rospy.is_shutdown() and \
8787
timeout_t > time.time():
8888
time.sleep(0.2)
8989

90-
self.failIf(self.test_curr is None, "no data from test")
91-
self.assertEquals('/rosjava_node', self.test_curr.caller_id)
92-
self.assertEquals('/node0', self.test_curr.orig_caller_id)
90+
self.assertFalse(self.test_curr is None, "no data from test")
91+
self.assertEqual('/rosjava_node', self.test_curr.caller_id)
92+
self.assertEqual('/node0', self.test_curr.orig_caller_id)
9393
t = self.test_curr.header.stamp.to_sec()
9494
# be really generous here, just need to be in the ballpark.
95-
self.assert_(abs(time.time() - t) < 60.)
95+
self.assertTrue(abs(time.time() - t) < 60.)
9696

9797
if __name__ == '__main__':
9898
import rostest

rosjava_benchmarks/scripts/pubsub_benchmark.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#!/usr/bin/python
1+
#!/usr/bin/env python
22
#
33
# Copyright (C) 2012 Google Inc.
44
#
@@ -32,7 +32,7 @@ def __init__(self):
3232

3333
def callback(self, _):
3434
with self.lock:
35-
self.count.next()
35+
next(self.count)
3636

3737
def run(self):
3838
tf_publisher = rospy.Publisher('tf', tf_msgs.tfMessage)
@@ -41,7 +41,7 @@ def run(self):
4141
while not rospy.is_shutdown():
4242
tf_publisher.publish(tf_msgs.tfMessage())
4343
if (rospy.Time.now() - self.time) > rospy.Duration(5):
44-
status_publisher.publish(std_msgs.String('%.2f Hz' % (self.count.next() / 5.0)))
44+
status_publisher.publish(std_msgs.String('%.2f Hz' % (next(self.count) / 5.0)))
4545
with self.lock:
4646
self.count = itertools.count()
4747
self.time = rospy.Time.now()

rosjava_test/scripts/serialized_message.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#!/usr/bin/python
1+
#!/usr/bin/env python
22
#
33
# Copyright (C) 2012 Google Inc.
44
#
@@ -23,15 +23,15 @@
2323

2424
__author__ = 'damonkohler@google.com (Damon Kohler)'
2525

26-
import StringIO
26+
import io
2727

2828
import roslib; roslib.load_manifest('rosjava_test')
2929
import rospy
3030

3131
import nav_msgs.msg as nav_msgs
3232

3333
message = nav_msgs.Odometry()
34-
buf = StringIO.StringIO()
34+
buf = io.StringIO()
3535
message.serialize(buf)
36-
print ''.join('0x%02x,' % ord(c) for c in buf.getvalue())[:-1]
36+
print(''.join('0x%02x,' % ord(c) for c in buf.getvalue())[:-1])
3737

0 commit comments

Comments
 (0)