Skip to content

Commit

Permalink
fix rosnode online test
Browse files Browse the repository at this point in the history
  • Loading branch information
lucasw committed Dec 31, 2023
1 parent 7ef82c1 commit 8957702
Showing 1 changed file with 9 additions and 11 deletions.
20 changes: 9 additions & 11 deletions tools/rosnode/test/check_rosnode_command_online.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,29 +53,27 @@ def run_for(cmd, secs):
class TestRosnodeOnline(unittest.TestCase):

def setUp(self):
self.vals = set()
self.msgs = {}

def callback(self, msg, val):
self.vals.add(val)
self.msgs[val] = msg
def callback(self, msg, key):
self.msgs[key] = msg

def test_rosnode(self):
topics = ['/chatter', '/foo/chatter', '/bar/chatter']

# wait for network to initialize
rospy.init_node('test')
nodes = ['/talker', '/foo/talker', '/bar/talker', rospy.get_caller_id()]
for i, t in enumerate(topics):
rospy.Subscriber(t, std_msgs.msg.String, self.callback, i)
all = set(range(0, len(topics)))

subs = {}
for t in topics:
subs[t] = rospy.Subscriber(t, std_msgs.msg.String, self.callback, t)

timeout_t = time.time() + 10.
while time.time() < timeout_t and self.vals != all:
while time.time() < timeout_t and len(self.msgs.keys()) < len(topics):
time.sleep(0.1)
self.assertEqual(self.vals, all, "failed to initialize graph correctly")

self.assertEqual(set(self.msgs.keys()), set(topics),
f"failed to initialize graph correctly {self.msgs}")

# network is initialized
cmd = 'rosnode'
Expand Down

0 comments on commit 8957702

Please sign in to comment.