@@ -67,41 +67,56 @@ def publish_message(self, level):
6767 rclpy .spin_once (self .node )
6868 return self .node .get_clock ().now ()
6969
70- def test_critical_publisher (self ):
70+ def critical_publisher_test (
71+ self , initial_state = DiagnosticStatus .OK , new_state = DiagnosticStatus .ERROR
72+ ):
7173 # Publish the ok message and wait till the toplevel state is received
72- state = DiagnosticStatus .OK
73- time_0 = self .publish_message (state )
74+ time_0 = self .publish_message (initial_state )
7475
75- assert (self .received_state [0 ] == state ), \
76+ assert (self .received_state [0 ] == initial_state ), \
7677 ('Received state is not the same as the sent state:'
77- + f"'{ self .received_state [0 ]} ' != '{ state } '" )
78+ + f"'{ self .received_state [0 ]} ' != '{ initial_state } '" )
7879 self .received_state .clear ()
7980
8081 # Publish the ok message and expect the toplevel state after 1 second period
81- time_1 = self .publish_message (state )
82+ time_1 = self .publish_message (initial_state )
8283 assert (time_1 - time_0 > rclpy .duration .Duration (seconds = 0.99 )), \
8384 'OK message received too early'
84- assert (self .received_state [0 ] == state ), \
85+ assert (self .received_state [0 ] == initial_state ), \
8586 ('Received state is not the same as the sent state:'
86- + f"'{ self .received_state [0 ]} ' != '{ state } '" )
87+ + f"'{ self .received_state [0 ]} ' != '{ initial_state } '" )
8788 self .received_state .clear ()
8889
8990 # Publish the message and expect the critical error message immediately
90- state = DiagnosticStatus .ERROR
91- time_2 = self .publish_message (state )
91+ time_2 = self .publish_message (new_state )
9292
9393 assert (time_2 - time_1 < rclpy .duration .Duration (seconds = 0.1 )), \
9494 'Critical error message not received within 0.1 second'
95- assert (self .received_state [0 ] == state ), \
95+ assert (self .received_state [0 ] == new_state ), \
9696 ('Received state is not the same as the sent state:'
97- + f"'{ self .received_state [0 ]} ' != '{ state } '" )
97+ + f"'{ self .received_state [0 ]} ' != '{ new_state } '" )
9898 self .received_state .clear ()
9999
100100 # Next error message should be sent at standard 1 second rate
101- time_3 = self .publish_message (state )
101+ time_3 = self .publish_message (new_state )
102102
103103 assert (time_3 - time_1 > rclpy .duration .Duration (seconds = 0.99 )), \
104104 'Periodic error message received too early'
105- assert (self .received_state [0 ] == state ), \
105+ assert (self .received_state [0 ] == new_state ), \
106106 ('Received state is not the same as the sent state:'
107- + f"'{ self .received_state [0 ]} ' != '{ state } '" )
107+ + f"'{ self .received_state [0 ]} ' != '{ new_state } '" )
108+
109+ def test_critical_publisher_ok_error (self ):
110+ self .critical_publisher_test (
111+ initial_state = DiagnosticStatus .OK , new_state = DiagnosticStatus .ERROR
112+ )
113+
114+ def test_critical_publisher_ok_warn (self ):
115+ self .critical_publisher_test (
116+ initial_state = DiagnosticStatus .OK , new_state = DiagnosticStatus .WARN
117+ )
118+
119+ def test_critical_publisher_warn_error (self ):
120+ self .critical_publisher_test (
121+ initial_state = DiagnosticStatus .WARN , new_state = DiagnosticStatus .ERROR
122+ )
0 commit comments