Skip to content

Commit fb4c6fc

Browse files
style(pre-commit): autofix
1 parent 40ff6d3 commit fb4c6fc

File tree

1 file changed

+13
-35
lines changed

1 file changed

+13
-35
lines changed

common/autoware_universe_utils/test/src/ros/test_diagnostics_module.cpp

+13-35
Original file line numberDiff line numberDiff line change
@@ -12,14 +12,15 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include <gtest/gtest.h>
15+
#include "autoware/universe_utils/ros/diagnostics_module.hpp"
16+
1617
#include <rclcpp/rclcpp.hpp>
1718

1819
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
1920
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
2021
#include <diagnostic_msgs/msg/key_value.hpp>
2122

22-
#include "autoware/universe_utils/ros/diagnostics_module.hpp"
23+
#include <gtest/gtest.h>
2324

2425
using autoware::universe_utils::DiagnosticsModule;
2526

@@ -47,21 +48,16 @@ TEST_F(TestDiagnosticsModule, ClearTest)
4748
// Add some key-value pairs and update level/message
4849
module.add_key_value("param1", 42);
4950
module.update_level_and_message(
50-
diagnostic_msgs::msg::DiagnosticStatus::WARN,
51-
"Something is not OK"
52-
);
53-
51+
diagnostic_msgs::msg::DiagnosticStatus::WARN, "Something is not OK");
52+
5453
// Call clear()
5554
module.clear();
5655

5756
// After calling clear(), publish and check the contents of the message
5857
diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr received_msg;
5958
auto sub = node_->create_subscription<diagnostic_msgs::msg::DiagnosticArray>(
6059
"/diagnostics", 10,
61-
[&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) {
62-
received_msg = msg;
63-
}
64-
);
60+
[&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) { received_msg = msg; });
6561

6662
// Publish the message
6763
module.publish(node_->now());
@@ -104,10 +100,7 @@ TEST_F(TestDiagnosticsModule, AddKeyValueTest)
104100
diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr received_msg;
105101
auto sub = node_->create_subscription<diagnostic_msgs::msg::DiagnosticArray>(
106102
"/diagnostics", 10,
107-
[&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) {
108-
received_msg = msg;
109-
}
110-
);
103+
[&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) { received_msg = msg; });
111104
module.publish(node_->now());
112105
rclcpp::spin_some(node_);
113106

@@ -138,7 +131,6 @@ TEST_F(TestDiagnosticsModule, AddKeyValueTest)
138131
EXPECT_EQ(status.message, "OK");
139132
}
140133

141-
142134
/*
143135
* Test update_level_and_message():
144136
* Verify that the level is updated to the highest severity and
@@ -149,33 +141,19 @@ TEST_F(TestDiagnosticsModule, UpdateLevelAndMessageTest)
149141
DiagnosticsModule module(node_.get(), "test_diagnostic");
150142

151143
// Initial status is level=OK(0), message=""
152-
module.update_level_and_message(
153-
diagnostic_msgs::msg::DiagnosticStatus::OK,
154-
"Initial OK"
155-
);
144+
module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::OK, "Initial OK");
156145
// Update to WARN (1)
157-
module.update_level_and_message(
158-
diagnostic_msgs::msg::DiagnosticStatus::WARN,
159-
"Low battery"
160-
);
146+
module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::WARN, "Low battery");
161147
// Update to ERROR (2)
162-
module.update_level_and_message(
163-
diagnostic_msgs::msg::DiagnosticStatus::ERROR,
164-
"Sensor failure"
165-
);
148+
module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Sensor failure");
166149
// Another WARN (1) after ERROR should not downgrade the overall level
167150
module.update_level_and_message(
168-
diagnostic_msgs::msg::DiagnosticStatus::WARN,
169-
"Should not override error"
170-
);
151+
diagnostic_msgs::msg::DiagnosticStatus::WARN, "Should not override error");
171152

172153
diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr received_msg;
173154
auto sub = node_->create_subscription<diagnostic_msgs::msg::DiagnosticArray>(
174155
"/diagnostics", 10,
175-
[&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) {
176-
received_msg = msg;
177-
}
178-
);
156+
[&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) { received_msg = msg; });
179157

180158
module.publish(node_->now());
181159
rclcpp::spin_some(node_);
@@ -195,4 +173,4 @@ TEST_F(TestDiagnosticsModule, UpdateLevelAndMessageTest)
195173
EXPECT_TRUE(final_message.find("Low battery") != std::string::npos);
196174
EXPECT_TRUE(final_message.find("Sensor failure") != std::string::npos);
197175
EXPECT_TRUE(final_message.find("Should not override error") != std::string::npos);
198-
}
176+
}

0 commit comments

Comments
 (0)