|
| 1 | +// Copyright 2024 Autoware Foundation |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include "autoware/universe_utils/ros/diagnostics_interface.hpp" |
| 16 | + |
| 17 | +#include <rclcpp/rclcpp.hpp> |
| 18 | + |
| 19 | +#include <diagnostic_msgs/msg/diagnostic_array.hpp> |
| 20 | +#include <diagnostic_msgs/msg/diagnostic_status.hpp> |
| 21 | +#include <diagnostic_msgs/msg/key_value.hpp> |
| 22 | + |
| 23 | +#include <gtest/gtest.h> |
| 24 | + |
| 25 | +#include <memory> |
| 26 | +#include <string> |
| 27 | + |
| 28 | +using autoware::universe_utils::DiagnosticInterface; |
| 29 | + |
| 30 | +class TestDiagnosticInterface : public ::testing::Test |
| 31 | +{ |
| 32 | +protected: |
| 33 | + void SetUp() override |
| 34 | + { |
| 35 | + // Create a test node |
| 36 | + node_ = std::make_shared<rclcpp::Node>("test_diagnostics_interface"); |
| 37 | + } |
| 38 | + |
| 39 | + // Automatically destroyed at the end of each test |
| 40 | + std::shared_ptr<rclcpp::Node> node_; |
| 41 | +}; |
| 42 | + |
| 43 | +/* |
| 44 | + * Test clear(): |
| 45 | + * Verify that calling clear() resets DiagnosticStatus values, level, and message. |
| 46 | + */ |
| 47 | +TEST_F(TestDiagnosticInterface, ClearTest) |
| 48 | +{ |
| 49 | + DiagnosticInterface module(node_.get(), "test_diagnostic"); |
| 50 | + |
| 51 | + // Add some key-value pairs and update level/message |
| 52 | + module.add_key_value("param1", 42); |
| 53 | + module.update_level_and_message( |
| 54 | + diagnostic_msgs::msg::DiagnosticStatus::WARN, "Something is not OK"); |
| 55 | + |
| 56 | + // Call clear() |
| 57 | + module.clear(); |
| 58 | + |
| 59 | + // After calling clear(), publish and check the contents of the message |
| 60 | + diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr received_msg; |
| 61 | + auto sub = node_->create_subscription<diagnostic_msgs::msg::DiagnosticArray>( |
| 62 | + "/diagnostics", 10, |
| 63 | + [&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) { received_msg = msg; }); |
| 64 | + |
| 65 | + // Publish the message |
| 66 | + module.publish(node_->now()); |
| 67 | + |
| 68 | + // Spin to allow the subscriber to receive messages |
| 69 | + rclcpp::spin_some(node_); |
| 70 | + |
| 71 | + ASSERT_NE(nullptr, received_msg); |
| 72 | + ASSERT_FALSE(received_msg->status.empty()); |
| 73 | + const auto & status = received_msg->status.front(); |
| 74 | + |
| 75 | + // After clear(), key-value pairs should be empty |
| 76 | + EXPECT_TRUE(status.values.empty()); |
| 77 | + |
| 78 | + // After clear(), level should be OK (=0) |
| 79 | + EXPECT_EQ(status.level, diagnostic_msgs::msg::DiagnosticStatus::OK); |
| 80 | + |
| 81 | + // After clear(), message is empty internally, |
| 82 | + // but "OK" is set during publishing when level == OK |
| 83 | + EXPECT_EQ(status.message, "OK"); |
| 84 | +} |
| 85 | + |
| 86 | +/* |
| 87 | + * Test add_key_value(): |
| 88 | + * Verify that adding the same key updates its value instead of adding a duplicate. |
| 89 | + */ |
| 90 | +TEST_F(TestDiagnosticInterface, AddKeyValueTest) |
| 91 | +{ |
| 92 | + DiagnosticInterface module(node_.get(), "test_diagnostic"); |
| 93 | + |
| 94 | + // Call the template version of add_key_value() with different types |
| 95 | + module.add_key_value("string_key", std::string("initial_value")); |
| 96 | + module.add_key_value("int_key", 123); |
| 97 | + module.add_key_value("bool_key", true); |
| 98 | + |
| 99 | + // Overwrite the value for "string_key" |
| 100 | + module.add_key_value("string_key", std::string("updated_value")); |
| 101 | + |
| 102 | + // Capture the published message to verify its contents |
| 103 | + diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr received_msg; |
| 104 | + auto sub = node_->create_subscription<diagnostic_msgs::msg::DiagnosticArray>( |
| 105 | + "/diagnostics", 10, |
| 106 | + [&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) { received_msg = msg; }); |
| 107 | + module.publish(node_->now()); |
| 108 | + rclcpp::spin_some(node_); |
| 109 | + |
| 110 | + ASSERT_NE(nullptr, received_msg); |
| 111 | + ASSERT_FALSE(received_msg->status.empty()); |
| 112 | + const auto & status = received_msg->status.front(); |
| 113 | + |
| 114 | + // Expect 3 key-value pairs |
| 115 | + ASSERT_EQ(status.values.size(), 3U); |
| 116 | + |
| 117 | + // Helper lambda to find a value by key |
| 118 | + auto find_value = [&](const std::string & key) -> std::string { |
| 119 | + for (const auto & kv : status.values) { |
| 120 | + if (kv.key == key) { |
| 121 | + return kv.value; |
| 122 | + } |
| 123 | + } |
| 124 | + return ""; |
| 125 | + }; |
| 126 | + |
| 127 | + EXPECT_EQ(find_value("string_key"), "updated_value"); |
| 128 | + EXPECT_EQ(find_value("int_key"), "123"); |
| 129 | + EXPECT_EQ(find_value("bool_key"), "True"); |
| 130 | + |
| 131 | + // Status level should still be OK |
| 132 | + EXPECT_EQ(status.level, diagnostic_msgs::msg::DiagnosticStatus::OK); |
| 133 | + // Message should be "OK" |
| 134 | + EXPECT_EQ(status.message, "OK"); |
| 135 | +} |
| 136 | + |
| 137 | +/* |
| 138 | + * Test update_level_and_message(): |
| 139 | + * Verify that the level is updated to the highest severity and |
| 140 | + * that messages are concatenated if level > OK. |
| 141 | + */ |
| 142 | +TEST_F(TestDiagnosticInterface, UpdateLevelAndMessageTest) |
| 143 | +{ |
| 144 | + DiagnosticInterface module(node_.get(), "test_diagnostic"); |
| 145 | + |
| 146 | + // Initial status is level=OK(0), message="" |
| 147 | + module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::OK, "Initial OK"); |
| 148 | + // Update to WARN (1) |
| 149 | + module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::WARN, "Low battery"); |
| 150 | + // Update to ERROR (2) |
| 151 | + module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Sensor failure"); |
| 152 | + // Another WARN (1) after ERROR should not downgrade the overall level |
| 153 | + module.update_level_and_message( |
| 154 | + diagnostic_msgs::msg::DiagnosticStatus::WARN, "Should not override error"); |
| 155 | + |
| 156 | + diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr received_msg; |
| 157 | + auto sub = node_->create_subscription<diagnostic_msgs::msg::DiagnosticArray>( |
| 158 | + "/diagnostics", 10, |
| 159 | + [&](diagnostic_msgs::msg::DiagnosticArray::ConstSharedPtr msg) { received_msg = msg; }); |
| 160 | + |
| 161 | + module.publish(node_->now()); |
| 162 | + rclcpp::spin_some(node_); |
| 163 | + |
| 164 | + ASSERT_NE(nullptr, received_msg); |
| 165 | + ASSERT_FALSE(received_msg->status.empty()); |
| 166 | + const auto & status = received_msg->status.front(); |
| 167 | + |
| 168 | + // Final level should be ERROR (2) |
| 169 | + EXPECT_EQ(status.level, diagnostic_msgs::msg::DiagnosticStatus::ERROR); |
| 170 | + |
| 171 | + // The message should contain all parts that were added when level > OK. |
| 172 | + // Thus, we expect something like: |
| 173 | + // "Low battery; Sensor failure; Should not override error" |
| 174 | + const std::string & final_message = status.message; |
| 175 | + EXPECT_FALSE(final_message.find("Initial OK") != std::string::npos); |
| 176 | + EXPECT_TRUE(final_message.find("Low battery") != std::string::npos); |
| 177 | + EXPECT_TRUE(final_message.find("Sensor failure") != std::string::npos); |
| 178 | + EXPECT_TRUE(final_message.find("Should not override error") != std::string::npos); |
| 179 | +} |
0 commit comments