|
| 1 | +import unittest |
| 2 | + |
| 3 | +import pytest |
| 4 | +import rclpy |
| 5 | + |
| 6 | +from launch import LaunchDescription |
| 7 | +from launch_ros.actions import Node |
| 8 | +from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus |
| 9 | +from launch_testing.actions import ReadyToTest |
| 10 | + |
| 11 | + |
| 12 | + |
| 13 | +@pytest.mark.launch_test |
| 14 | +def generate_test_description(): |
| 15 | + # Launch the aggregator |
| 16 | + parameters = [{'analyzers.test.type': 'diagnostic_aggregator/GenericAnalyzer'}, |
| 17 | + {'analyzers.test.path': 'Test'}, |
| 18 | + {'analyzers.test.contains': ['test']}, |
| 19 | + {'path': 'Base'}, |
| 20 | + {'critical': True}] |
| 21 | + |
| 22 | + aggregator_cmd = Node( |
| 23 | + package='diagnostic_aggregator', |
| 24 | + executable='aggregator_node', |
| 25 | + name='diagnostic_aggregator', |
| 26 | + parameters=parameters) |
| 27 | + |
| 28 | + ld = LaunchDescription() |
| 29 | + |
| 30 | + # Launch the node |
| 31 | + ld.add_action(aggregator_cmd) |
| 32 | + ld.add_action(ReadyToTest()) |
| 33 | + return ld |
| 34 | + |
| 35 | + |
| 36 | +class TestProcessOutput(unittest.TestCase): |
| 37 | + |
| 38 | + @ classmethod |
| 39 | + def setUpClass(cls): |
| 40 | + # Initialize the ROS context for the test node |
| 41 | + rclpy.init() |
| 42 | + |
| 43 | + @ classmethod |
| 44 | + def tearDownClass(cls): |
| 45 | + # Shutdown the ROS context |
| 46 | + rclpy.shutdown() |
| 47 | + |
| 48 | + def setUp(self): |
| 49 | + # Create a ROS node for tests |
| 50 | + self.node = rclpy.create_node('test_node') |
| 51 | + self.publisher = self.node.create_publisher(DiagnosticArray, '/diagnostics', 1) |
| 52 | + self.subscriber = self.node.create_subscription( |
| 53 | + DiagnosticStatus, |
| 54 | + '/diagnostics_toplevel_state', |
| 55 | + lambda msg: self.received_state.append(msg.level), |
| 56 | + 1) |
| 57 | + self.received_state = [] |
| 58 | + |
| 59 | + def tearDown(self): |
| 60 | + self.node.destroy_node() |
| 61 | + |
| 62 | + def publish_message(self, level): |
| 63 | + msg = DiagnosticArray() |
| 64 | + msg.status.append(DiagnosticStatus()) |
| 65 | + msg.status[0].level = level |
| 66 | + msg.status[0].name = 'test status' |
| 67 | + self.publisher.publish(msg) |
| 68 | + while len(self.received_state) == 0: |
| 69 | + rclpy.spin_once(self.node) |
| 70 | + |
| 71 | + return self.node.get_clock().now() |
| 72 | + |
| 73 | + def test_ok_state(self): |
| 74 | + # Publish the ok message and wait till the toplevel state is received |
| 75 | + state = DiagnosticStatus.OK |
| 76 | + time_0 = self.publish_message(state) |
| 77 | + |
| 78 | + assert (self.received_state[0] == state), \ |
| 79 | + 'Received state is not the same as the sent state' |
| 80 | + self.received_state.clear() |
| 81 | + |
| 82 | + # Publish the ok message and expect the toplevel state after 1 second period |
| 83 | + time_1 = self.publish_message(state) |
| 84 | + assert (time_1 - time_0 > rclpy.duration.Duration(seconds=0.99)), \ |
| 85 | + 'OK message received too early' |
| 86 | + assert (self.received_state[0] == state), \ |
| 87 | + 'Received state is not the same as the sent state' |
| 88 | + self.received_state.clear() |
| 89 | + |
| 90 | + # Publish the message and expect the critical error message immediately |
| 91 | + state = DiagnosticStatus.ERROR |
| 92 | + time_2 = self.publish_message(state) |
| 93 | + |
| 94 | + assert (time_2 - time_1 < rclpy.duration.Duration(seconds=0.1)), \ |
| 95 | + 'Critical error message not received within 0.1 second' |
| 96 | + assert (self.received_state[0] == state), \ |
| 97 | + 'Received state is not the same as the sent state' |
| 98 | + self.received_state.clear() |
| 99 | + |
| 100 | + # Next error message should be sent at standard 1 second rate |
| 101 | + time_3 = self.publish_message(state) |
| 102 | + |
| 103 | + assert (time_3 - time_1 > rclpy.duration.Duration(seconds=0.99)), \ |
| 104 | + 'Periodic error message received too early' |
| 105 | + assert (self.received_state[0] == state), \ |
| 106 | + 'Received state is not the same as the sent state' |
0 commit comments