From f87513b76de852ed9caacea49b92ffcb65d8aadb Mon Sep 17 00:00:00 2001 From: Shubham Gawande Date: Wed, 28 Feb 2024 18:00:26 +0100 Subject: [PATCH] added test case for number of robots in mrs --- test/test_multi_robot_system.py | 34 +++++++++++++++++++++++++++++++++ 1 file changed, 34 insertions(+) create mode 100644 test/test_multi_robot_system.py diff --git a/test/test_multi_robot_system.py b/test/test_multi_robot_system.py new file mode 100644 index 0000000..072c8ea --- /dev/null +++ b/test/test_multi_robot_system.py @@ -0,0 +1,34 @@ +import sys +import unittest +import rclpy +from rclpy.node import Node + +class TestNumberOfRobots(unittest.TestCase): + @classmethod + def setUpClass(cls): + cls.expected_number_of_robots = int(sys.argv[1]) # Get expected number of robots from arguments + rclpy.init(args=sys.argv) + + @classmethod + def tearDownClass(cls): + rclpy.shutdown() + + def test_robot_count(self): + node = rclpy.create_node('test_robot_count_node') + discovered_robots = [] + + def topic_callback(topic_list): + nonlocal discovered_robots + for topic_name, _ in topic_list: + if 'joint_states' in topic_name and topic_name.startswith('/robot_'): + robot_name = topic_name.split('/')[1] + if robot_name not in discovered_robots: + discovered_robots.append(robot_name) + + node.get_topic_names_and_types(node_name=None, node_namespace=None, no_demangle=False, callback=topic_callback) + rclpy.spin_once(node, timeout_sec=1.0) + self.assertEqual(len(discovered_robots), self.expected_number_of_robots) + node.destroy_node() + +if __name__ == '__main__': + unittest.main() \ No newline at end of file