Skip to content

Commit

Permalink
fix: flake8
Browse files Browse the repository at this point in the history
  • Loading branch information
outrider-jhulas committed Nov 24, 2023
1 parent 2d40c6c commit 2e69d78
Showing 1 changed file with 16 additions and 15 deletions.
31 changes: 16 additions & 15 deletions diagnostic_aggregator/test/test_critical_pub.py
Original file line number Diff line number Diff line change
@@ -1,22 +1,23 @@
import unittest

import pytest
import rclpy
import unittest

from launch import LaunchDescription
from launch_ros.actions import Node
from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
from launch_testing.actions import ReadyToTest

from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus


@pytest.mark.launch_test
def generate_test_description():
# Launch the aggregator
parameters = [{"analyzers.test.type": "diagnostic_aggregator/GenericAnalyzer"},
{"analyzers.test.path": "Test"},
{"analyzers.test.contains": ["test"]},
{"path": "Base"},
{"critical": True}]
parameters = [{'analyzers.test.type': 'diagnostic_aggregator/GenericAnalyzer'},
{'analyzers.test.path': 'Test'},
{'analyzers.test.contains': ['test']},
{'path': 'Base'},
{'critical': True}]

aggregator_cmd = Node(
package='diagnostic_aggregator',
Expand Down Expand Up @@ -62,7 +63,7 @@ def publish_message(self, level):
msg = DiagnosticArray()
msg.status.append(DiagnosticStatus())
msg.status[0].level = level
msg.status[0].name = "test status"
msg.status[0].name = 'test status'
self.publisher.publish(msg)
while len(self.received_state) == 0:
rclpy.spin_once(self.node)
Expand All @@ -75,31 +76,31 @@ def test_ok_state(self):
time_0 = self.publish_message(state)

assert (self.received_state[0] == state), \
"Received state is not the same as the sent state"
'Received state is not the same as the sent state'
self.received_state.clear()

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

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

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

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

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

0 comments on commit 2e69d78

Please sign in to comment.