Skip to content

Commit 16d5cb1

Browse files
feat!: move diagnostics_module from localization_util to unverse_utils (#9714)
* feat!: move diagnostics_module from localization_util to unverse_utils Signed-off-by: kminoda <koji.minoda@tier4.jp> * remove diagnostics module from localization_util Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * minor fix in pose_initializer Signed-off-by: kminoda <koji.minoda@tier4.jp> * add test Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * remove unnecessary declaration Signed-off-by: kminoda <koji.minoda@tier4.jp> * module -> interface Signed-off-by: kminoda <koji.minoda@tier4.jp> * remove unnecessary equal expression Signed-off-by: kminoda <koji.minoda@tier4.jp> * revert the remove of template function Signed-off-by: kminoda <koji.minoda@tier4.jp> * style(pre-commit): autofix * use overload instead Signed-off-by: kminoda <koji.minoda@tier4.jp> * include what you use -- test_diagnostics_interface.cpp Signed-off-by: kminoda <koji.minoda@tier4.jp> --------- Signed-off-by: kminoda <koji.minoda@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 421ec7d commit 16d5cb1

File tree

19 files changed

+261
-87
lines changed

19 files changed

+261
-87
lines changed

common/autoware_universe_utils/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@ ament_auto_add_library(autoware_universe_utils SHARED
2121
src/geometry/sat_2d.cpp
2222
src/math/sin_table.cpp
2323
src/math/trigonometry.cpp
24+
src/ros/diagnostics_interface.cpp
2425
src/ros/msg_operation.cpp
2526
src/ros/marker_helper.cpp
2627
src/ros/logger_level_configure.cpp

localization/autoware_localization_util/include/autoware/localization_util/diagnostics_module.hpp common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp

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

15-
#ifndef AUTOWARE__LOCALIZATION_UTIL__DIAGNOSTICS_MODULE_HPP_
16-
#define AUTOWARE__LOCALIZATION_UTIL__DIAGNOSTICS_MODULE_HPP_
15+
#ifndef AUTOWARE__UNIVERSE_UTILS__ROS__DIAGNOSTICS_INTERFACE_HPP_
16+
#define AUTOWARE__UNIVERSE_UTILS__ROS__DIAGNOSTICS_INTERFACE_HPP_
1717

1818
#include <rclcpp/rclcpp.hpp>
1919

@@ -22,16 +22,18 @@
2222
#include <string>
2323
#include <vector>
2424

25-
namespace autoware::localization_util
25+
namespace autoware::universe_utils
2626
{
27-
class DiagnosticsModule
27+
class DiagnosticInterface
2828
{
2929
public:
30-
DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name);
30+
DiagnosticInterface(rclcpp::Node * node, const std::string & diagnostic_name);
3131
void clear();
3232
void add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg);
3333
template <typename T>
3434
void add_key_value(const std::string & key, const T & value);
35+
void add_key_value(const std::string & key, const std::string & value);
36+
void add_key_value(const std::string & key, bool value);
3537
void update_level_and_message(const int8_t level, const std::string & message);
3638
void publish(const rclcpp::Time & publish_time_stamp);
3739

@@ -46,19 +48,14 @@ class DiagnosticsModule
4648
};
4749

4850
template <typename T>
49-
void DiagnosticsModule::add_key_value(const std::string & key, const T & value)
51+
void DiagnosticInterface::add_key_value(const std::string & key, const T & value)
5052
{
5153
diagnostic_msgs::msg::KeyValue key_value;
5254
key_value.key = key;
5355
key_value.value = std::to_string(value);
5456
add_key_value(key_value);
5557
}
5658

57-
template <>
58-
void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value);
59-
template <>
60-
void DiagnosticsModule::add_key_value(const std::string & key, const bool & value);
59+
} // namespace autoware::universe_utils
6160

62-
} // namespace autoware::localization_util
63-
64-
#endif // AUTOWARE__LOCALIZATION_UTIL__DIAGNOSTICS_MODULE_HPP_
61+
#endif // AUTOWARE__UNIVERSE_UTILS__ROS__DIAGNOSTICS_INTERFACE_HPP_

localization/autoware_localization_util/src/diagnostics_module.cpp common/autoware_universe_utils/src/ros/diagnostics_interface.cpp

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

15-
#include "autoware/localization_util/diagnostics_module.hpp"
15+
#include "autoware/universe_utils/ros/diagnostics_interface.hpp"
1616

1717
#include <rclcpp/rclcpp.hpp>
1818

@@ -21,9 +21,9 @@
2121
#include <algorithm>
2222
#include <string>
2323

24-
namespace autoware::localization_util
24+
namespace autoware::universe_utils
2525
{
26-
DiagnosticsModule::DiagnosticsModule(rclcpp::Node * node, const std::string & diagnostic_name)
26+
DiagnosticInterface::DiagnosticInterface(rclcpp::Node * node, const std::string & diagnostic_name)
2727
: clock_(node->get_clock())
2828
{
2929
diagnostics_pub_ =
@@ -34,7 +34,7 @@ DiagnosticsModule::DiagnosticsModule(rclcpp::Node * node, const std::string & di
3434
diagnostics_status_msg_.hardware_id = node->get_name();
3535
}
3636

37-
void DiagnosticsModule::clear()
37+
void DiagnosticInterface::clear()
3838
{
3939
diagnostics_status_msg_.values.clear();
4040
diagnostics_status_msg_.values.shrink_to_fit();
@@ -43,7 +43,7 @@ void DiagnosticsModule::clear()
4343
diagnostics_status_msg_.message = "";
4444
}
4545

46-
void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg)
46+
void DiagnosticInterface::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg)
4747
{
4848
auto it = std::find_if(
4949
std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values),
@@ -56,25 +56,23 @@ void DiagnosticsModule::add_key_value(const diagnostic_msgs::msg::KeyValue & key
5656
}
5757
}
5858

59-
template <>
60-
void DiagnosticsModule::add_key_value(const std::string & key, const std::string & value)
59+
void DiagnosticInterface::add_key_value(const std::string & key, const std::string & value)
6160
{
6261
diagnostic_msgs::msg::KeyValue key_value;
6362
key_value.key = key;
6463
key_value.value = value;
6564
add_key_value(key_value);
6665
}
6766

68-
template <>
69-
void DiagnosticsModule::add_key_value(const std::string & key, const bool & value)
67+
void DiagnosticInterface::add_key_value(const std::string & key, bool value)
7068
{
7169
diagnostic_msgs::msg::KeyValue key_value;
7270
key_value.key = key;
7371
key_value.value = value ? "True" : "False";
7472
add_key_value(key_value);
7573
}
7674

77-
void DiagnosticsModule::update_level_and_message(const int8_t level, const std::string & message)
75+
void DiagnosticInterface::update_level_and_message(const int8_t level, const std::string & message)
7876
{
7977
if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) {
8078
if (!diagnostics_status_msg_.message.empty()) {
@@ -87,12 +85,12 @@ void DiagnosticsModule::update_level_and_message(const int8_t level, const std::
8785
}
8886
}
8987

90-
void DiagnosticsModule::publish(const rclcpp::Time & publish_time_stamp)
88+
void DiagnosticInterface::publish(const rclcpp::Time & publish_time_stamp)
9189
{
9290
diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp));
9391
}
9492

95-
diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::create_diagnostics_array(
93+
diagnostic_msgs::msg::DiagnosticArray DiagnosticInterface::create_diagnostics_array(
9694
const rclcpp::Time & publish_time_stamp) const
9795
{
9896
diagnostic_msgs::msg::DiagnosticArray diagnostics_msg;
@@ -105,4 +103,4 @@ diagnostic_msgs::msg::DiagnosticArray DiagnosticsModule::create_diagnostics_arra
105103

106104
return diagnostics_msg;
107105
}
108-
} // namespace autoware::localization_util
106+
} // namespace autoware::universe_utils
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,179 @@
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+
}

localization/autoware_gyro_odometer/src/gyro_odometer_core.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,7 @@ GyroOdometerNode::GyroOdometerNode(const rclcpp::NodeOptions & node_options)
7373
"twist_with_covariance", rclcpp::QoS{10});
7474

7575
diagnostics_ =
76-
std::make_unique<autoware::localization_util::DiagnosticsModule>(this, "gyro_odometer_status");
76+
std::make_unique<autoware::universe_utils::DiagnosticInterface>(this, "gyro_odometer_status");
7777

7878
// TODO(YamatoAndo) createTimer
7979
}

localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
#ifndef GYRO_ODOMETER_CORE_HPP_
1616
#define GYRO_ODOMETER_CORE_HPP_
1717

18-
#include "autoware/localization_util/diagnostics_module.hpp"
18+
#include "autoware/universe_utils/ros/diagnostics_interface.hpp"
1919
#include "autoware/universe_utils/ros/logger_level_configure.hpp"
2020
#include "autoware/universe_utils/ros/msg_covariance.hpp"
2121
#include "autoware/universe_utils/ros/transform_listener.hpp"
@@ -80,7 +80,7 @@ class GyroOdometerNode : public rclcpp::Node
8080
std::deque<geometry_msgs::msg::TwistWithCovarianceStamped> vehicle_twist_queue_;
8181
std::deque<sensor_msgs::msg::Imu> gyro_queue_;
8282

83-
std::unique_ptr<autoware::localization_util::DiagnosticsModule> diagnostics_;
83+
std::unique_ptr<autoware::universe_utils::DiagnosticInterface> diagnostics_;
8484
};
8585

8686
} // namespace autoware::gyro_odometer

0 commit comments

Comments
 (0)