Skip to content

Commit 2e69d78

Browse files
fix: flake8
1 parent 2d40c6c commit 2e69d78

File tree

1 file changed

+16
-15
lines changed

1 file changed

+16
-15
lines changed

diagnostic_aggregator/test/test_critical_pub.py

Lines changed: 16 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -1,22 +1,23 @@
1+
import unittest
2+
13
import pytest
24
import rclpy
3-
import unittest
45

56
from launch import LaunchDescription
67
from launch_ros.actions import Node
8+
from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
79
from launch_testing.actions import ReadyToTest
810

9-
from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
1011

1112

1213
@pytest.mark.launch_test
1314
def generate_test_description():
1415
# Launch the aggregator
15-
parameters = [{"analyzers.test.type": "diagnostic_aggregator/GenericAnalyzer"},
16-
{"analyzers.test.path": "Test"},
17-
{"analyzers.test.contains": ["test"]},
18-
{"path": "Base"},
19-
{"critical": True}]
16+
parameters = [{'analyzers.test.type': 'diagnostic_aggregator/GenericAnalyzer'},
17+
{'analyzers.test.path': 'Test'},
18+
{'analyzers.test.contains': ['test']},
19+
{'path': 'Base'},
20+
{'critical': True}]
2021

2122
aggregator_cmd = Node(
2223
package='diagnostic_aggregator',
@@ -62,7 +63,7 @@ def publish_message(self, level):
6263
msg = DiagnosticArray()
6364
msg.status.append(DiagnosticStatus())
6465
msg.status[0].level = level
65-
msg.status[0].name = "test status"
66+
msg.status[0].name = 'test status'
6667
self.publisher.publish(msg)
6768
while len(self.received_state) == 0:
6869
rclpy.spin_once(self.node)
@@ -75,31 +76,31 @@ def test_ok_state(self):
7576
time_0 = self.publish_message(state)
7677

7778
assert (self.received_state[0] == state), \
78-
"Received state is not the same as the sent state"
79+
'Received state is not the same as the sent state'
7980
self.received_state.clear()
8081

8182
# Publish the ok message and expect the toplevel state after 1 second period
8283
time_1 = self.publish_message(state)
8384
assert (time_1 - time_0 > rclpy.duration.Duration(seconds=0.99)), \
84-
"OK message received too early"
85+
'OK message received too early'
8586
assert (self.received_state[0] == state), \
86-
"Received state is not the same as the sent state"
87+
'Received state is not the same as the sent state'
8788
self.received_state.clear()
8889

8990
# Publish the message and expect the critical error message immediately
9091
state = DiagnosticStatus.ERROR
9192
time_2 = self.publish_message(state)
9293

9394
assert (time_2 - time_1 < rclpy.duration.Duration(seconds=0.1)), \
94-
"Critical error message not received within 0.1 second"
95+
'Critical error message not received within 0.1 second'
9596
assert (self.received_state[0] == state), \
96-
"Received state is not the same as the sent state"
97+
'Received state is not the same as the sent state'
9798
self.received_state.clear()
9899

99100
# Next error message should be sent at standard 1 second rate
100101
time_3 = self.publish_message(state)
101102

102103
assert (time_3 - time_1 > rclpy.duration.Duration(seconds=0.99)), \
103-
"Periodic error message received too early"
104+
'Periodic error message received too early'
104105
assert (self.received_state[0] == state), \
105-
"Received state is not the same as the sent state"
106+
'Received state is not the same as the sent state'

0 commit comments

Comments
 (0)