Skip to content

Commit 01cc946

Browse files
committed
refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface
Signed-off-by: kminoda <koji.minoda@tier4.jp>
1 parent 3d53032 commit 01cc946

File tree

15 files changed

+49
-49
lines changed

15 files changed

+49
-49
lines changed

common/autoware_universe_utils/include/autoware/universe_utils/ros/diagnostics_interface.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -24,10 +24,10 @@
2424

2525
namespace autoware::universe_utils
2626
{
27-
class DiagnosticInterface
27+
class DiagnosticsInterface
2828
{
2929
public:
30-
DiagnosticInterface(rclcpp::Node * node, const std::string & diagnostic_name);
30+
DiagnosticsInterface(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>
@@ -48,7 +48,7 @@ class DiagnosticInterface
4848
};
4949

5050
template <typename T>
51-
void DiagnosticInterface::add_key_value(const std::string & key, const T & value)
51+
void DiagnosticsInterface::add_key_value(const std::string & key, const T & value)
5252
{
5353
diagnostic_msgs::msg::KeyValue key_value;
5454
key_value.key = key;

common/autoware_universe_utils/src/ros/diagnostics_interface.cpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323

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

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

46-
void DiagnosticInterface::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg)
46+
void DiagnosticsInterface::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,23 +56,23 @@ void DiagnosticInterface::add_key_value(const diagnostic_msgs::msg::KeyValue & k
5656
}
5757
}
5858

59-
void DiagnosticInterface::add_key_value(const std::string & key, const std::string & value)
59+
void DiagnosticsInterface::add_key_value(const std::string & key, const std::string & value)
6060
{
6161
diagnostic_msgs::msg::KeyValue key_value;
6262
key_value.key = key;
6363
key_value.value = value;
6464
add_key_value(key_value);
6565
}
6666

67-
void DiagnosticInterface::add_key_value(const std::string & key, bool value)
67+
void DiagnosticsInterface::add_key_value(const std::string & key, bool value)
6868
{
6969
diagnostic_msgs::msg::KeyValue key_value;
7070
key_value.key = key;
7171
key_value.value = value ? "True" : "False";
7272
add_key_value(key_value);
7373
}
7474

75-
void DiagnosticInterface::update_level_and_message(const int8_t level, const std::string & message)
75+
void DiagnosticsInterface::update_level_and_message(const int8_t level, const std::string & message)
7676
{
7777
if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) {
7878
if (!diagnostics_status_msg_.message.empty()) {
@@ -85,12 +85,12 @@ void DiagnosticInterface::update_level_and_message(const int8_t level, const std
8585
}
8686
}
8787

88-
void DiagnosticInterface::publish(const rclcpp::Time & publish_time_stamp)
88+
void DiagnosticsInterface::publish(const rclcpp::Time & publish_time_stamp)
8989
{
9090
diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp));
9191
}
9292

93-
diagnostic_msgs::msg::DiagnosticArray DiagnosticInterface::create_diagnostics_array(
93+
diagnostic_msgs::msg::DiagnosticArray DiagnosticsInterface::create_diagnostics_array(
9494
const rclcpp::Time & publish_time_stamp) const
9595
{
9696
diagnostic_msgs::msg::DiagnosticArray diagnostics_msg;

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

+8-8
Original file line numberDiff line numberDiff line change
@@ -25,9 +25,9 @@
2525
#include <memory>
2626
#include <string>
2727

28-
using autoware::universe_utils::DiagnosticInterface;
28+
using autoware::universe_utils::DiagnosticsInterface;
2929

30-
class TestDiagnosticInterface : public ::testing::Test
30+
class TestDiagnosticsInterface : public ::testing::Test
3131
{
3232
protected:
3333
void SetUp() override
@@ -44,9 +44,9 @@ class TestDiagnosticInterface : public ::testing::Test
4444
* Test clear():
4545
* Verify that calling clear() resets DiagnosticStatus values, level, and message.
4646
*/
47-
TEST_F(TestDiagnosticInterface, ClearTest)
47+
TEST_F(TestDiagnosticsInterface, ClearTest)
4848
{
49-
DiagnosticInterface module(node_.get(), "test_diagnostic");
49+
DiagnosticsInterface module(node_.get(), "test_diagnostic");
5050

5151
// Add some key-value pairs and update level/message
5252
module.add_key_value("param1", 42);
@@ -87,9 +87,9 @@ TEST_F(TestDiagnosticInterface, ClearTest)
8787
* Test add_key_value():
8888
* Verify that adding the same key updates its value instead of adding a duplicate.
8989
*/
90-
TEST_F(TestDiagnosticInterface, AddKeyValueTest)
90+
TEST_F(TestDiagnosticsInterface, AddKeyValueTest)
9191
{
92-
DiagnosticInterface module(node_.get(), "test_diagnostic");
92+
DiagnosticsInterface module(node_.get(), "test_diagnostic");
9393

9494
// Call the template version of add_key_value() with different types
9595
module.add_key_value("string_key", std::string("initial_value"));
@@ -139,9 +139,9 @@ TEST_F(TestDiagnosticInterface, AddKeyValueTest)
139139
* Verify that the level is updated to the highest severity and
140140
* that messages are concatenated if level > OK.
141141
*/
142-
TEST_F(TestDiagnosticInterface, UpdateLevelAndMessageTest)
142+
TEST_F(TestDiagnosticsInterface, UpdateLevelAndMessageTest)
143143
{
144-
DiagnosticInterface module(node_.get(), "test_diagnostic");
144+
DiagnosticsInterface module(node_.get(), "test_diagnostic");
145145

146146
// Initial status is level=OK(0), message=""
147147
module.update_level_and_message(diagnostic_msgs::msg::DiagnosticStatus::OK, "Initial OK");

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::universe_utils::DiagnosticInterface>(this, "gyro_odometer_status");
76+
std::make_unique<autoware::universe_utils::DiagnosticsInterface>(this, "gyro_odometer_status");
7777

7878
// TODO(YamatoAndo) createTimer
7979
}

localization/autoware_gyro_odometer/src/gyro_odometer_core.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -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::universe_utils::DiagnosticInterface> diagnostics_;
83+
std::unique_ptr<autoware::universe_utils::DiagnosticsInterface> diagnostics_;
8484
};
8585

8686
} // namespace autoware::gyro_odometer

localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,7 @@ LidarMarkerLocalizer::LidarMarkerLocalizer(const rclcpp::NodeOptions & node_opti
125125
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_, this, false);
126126

127127
diagnostics_interface_.reset(
128-
new autoware::universe_utils::DiagnosticInterface(this, "marker_detection_status"));
128+
new autoware::universe_utils::DiagnosticsInterface(this, "marker_detection_status"));
129129
}
130130

131131
void LidarMarkerLocalizer::initialize_diagnostics()

localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,7 @@ class LidarMarkerLocalizer : public rclcpp::Node
134134
rclcpp::Publisher<PoseWithCovarianceStamped>::SharedPtr pub_debug_pose_with_covariance_;
135135
rclcpp::Publisher<PointCloud2>::SharedPtr pub_marker_pointcloud_;
136136

137-
std::shared_ptr<autoware::universe_utils::DiagnosticInterface> diagnostics_interface_;
137+
std::shared_ptr<autoware::universe_utils::DiagnosticsInterface> diagnostics_interface_;
138138

139139
Param param_;
140140
bool is_activated_;

localization/autoware_localization_error_monitor/src/localization_error_monitor.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -59,7 +59,7 @@ LocalizationErrorMonitor::LocalizationErrorMonitor(const rclcpp::NodeOptions & o
5959
logger_configure_ = std::make_unique<autoware::universe_utils::LoggerLevelConfigure>(this);
6060

6161
diagnostics_error_monitor_ =
62-
std::make_unique<autoware::universe_utils::DiagnosticInterface>(this, "ellipse_error_status");
62+
std::make_unique<autoware::universe_utils::DiagnosticsInterface>(this, "ellipse_error_status");
6363
}
6464

6565
void LocalizationErrorMonitor::on_odom(nav_msgs::msg::Odometry::ConstSharedPtr input_msg)

localization/autoware_localization_error_monitor/src/localization_error_monitor.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ class LocalizationErrorMonitor : public rclcpp::Node
3939

4040
std::unique_ptr<autoware::universe_utils::LoggerLevelConfigure> logger_configure_;
4141

42-
std::unique_ptr<autoware::universe_utils::DiagnosticInterface> diagnostics_error_monitor_;
42+
std::unique_ptr<autoware::universe_utils::DiagnosticsInterface> diagnostics_error_monitor_;
4343

4444
double scale_;
4545
double error_ellipse_size_;

localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/map_update_module.hpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@
4242

4343
namespace autoware::ndt_scan_matcher
4444
{
45-
using DiagnosticInterface = autoware::universe_utils::DiagnosticInterface;
45+
using DiagnosticsInterface = autoware::universe_utils::DiagnosticsInterface;
4646

4747
class MapUpdateModule
4848
{
@@ -63,19 +63,19 @@ class MapUpdateModule
6363

6464
void callback_timer(
6565
const bool is_activated, const std::optional<geometry_msgs::msg::Point> & position,
66-
std::unique_ptr<DiagnosticInterface> & diagnostics_ptr);
66+
std::unique_ptr<DiagnosticsInterface> & diagnostics_ptr);
6767

6868
[[nodiscard]] bool should_update_map(
6969
const geometry_msgs::msg::Point & position,
70-
std::unique_ptr<DiagnosticInterface> & diagnostics_ptr);
70+
std::unique_ptr<DiagnosticsInterface> & diagnostics_ptr);
7171

7272
void update_map(
7373
const geometry_msgs::msg::Point & position,
74-
std::unique_ptr<DiagnosticInterface> & diagnostics_ptr);
74+
std::unique_ptr<DiagnosticsInterface> & diagnostics_ptr);
7575
// Update the specified NDT
7676
bool update_ndt(
7777
const geometry_msgs::msg::Point & position, NdtType & ndt,
78-
std::unique_ptr<DiagnosticInterface> & diagnostics_ptr);
78+
std::unique_ptr<DiagnosticsInterface> & diagnostics_ptr);
7979
void publish_partial_pcd_map();
8080

8181
rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr loaded_pcd_pub_;

localization/autoware_ndt_scan_matcher/include/autoware/ndt_scan_matcher/ndt_scan_matcher_core.hpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -211,12 +211,12 @@ class NDTScanMatcher : public rclcpp::Node
211211
std::unique_ptr<autoware::localization_util::SmartPoseBuffer> regularization_pose_buffer_;
212212

213213
std::atomic<bool> is_activated_;
214-
std::unique_ptr<DiagnosticInterface> diagnostics_scan_points_;
215-
std::unique_ptr<DiagnosticInterface> diagnostics_initial_pose_;
216-
std::unique_ptr<DiagnosticInterface> diagnostics_regularization_pose_;
217-
std::unique_ptr<DiagnosticInterface> diagnostics_map_update_;
218-
std::unique_ptr<DiagnosticInterface> diagnostics_ndt_align_;
219-
std::unique_ptr<DiagnosticInterface> diagnostics_trigger_node_;
214+
std::unique_ptr<DiagnosticsInterface> diagnostics_scan_points_;
215+
std::unique_ptr<DiagnosticsInterface> diagnostics_initial_pose_;
216+
std::unique_ptr<DiagnosticsInterface> diagnostics_regularization_pose_;
217+
std::unique_ptr<DiagnosticsInterface> diagnostics_map_update_;
218+
std::unique_ptr<DiagnosticsInterface> diagnostics_ndt_align_;
219+
std::unique_ptr<DiagnosticsInterface> diagnostics_trigger_node_;
220220
std::unique_ptr<MapUpdateModule> map_update_module_;
221221
std::unique_ptr<autoware::universe_utils::LoggerLevelConfigure> logger_configure_;
222222

localization/autoware_ndt_scan_matcher/src/map_update_module.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ MapUpdateModule::MapUpdateModule(
5656

5757
void MapUpdateModule::callback_timer(
5858
const bool is_activated, const std::optional<geometry_msgs::msg::Point> & position,
59-
std::unique_ptr<DiagnosticInterface> & diagnostics_ptr)
59+
std::unique_ptr<DiagnosticsInterface> & diagnostics_ptr)
6060
{
6161
// check is_activated
6262
diagnostics_ptr->add_key_value("is_activated", is_activated);
@@ -87,7 +87,7 @@ void MapUpdateModule::callback_timer(
8787

8888
bool MapUpdateModule::should_update_map(
8989
const geometry_msgs::msg::Point & position,
90-
std::unique_ptr<DiagnosticInterface> & diagnostics_ptr)
90+
std::unique_ptr<DiagnosticsInterface> & diagnostics_ptr)
9191
{
9292
last_update_position_mtx_.lock();
9393

@@ -143,7 +143,7 @@ bool MapUpdateModule::out_of_map_range(const geometry_msgs::msg::Point & positio
143143

144144
void MapUpdateModule::update_map(
145145
const geometry_msgs::msg::Point & position,
146-
std::unique_ptr<DiagnosticInterface> & diagnostics_ptr)
146+
std::unique_ptr<DiagnosticsInterface> & diagnostics_ptr)
147147
{
148148
diagnostics_ptr->add_key_value("is_need_rebuild", need_rebuild_);
149149

@@ -231,7 +231,7 @@ void MapUpdateModule::update_map(
231231

232232
bool MapUpdateModule::update_ndt(
233233
const geometry_msgs::msg::Point & position, NdtType & ndt,
234-
std::unique_ptr<DiagnosticInterface> & diagnostics_ptr)
234+
std::unique_ptr<DiagnosticsInterface> & diagnostics_ptr)
235235
{
236236
diagnostics_ptr->add_key_value("maps_size_before", ndt.getCurrentMapIDs().size());
237237

localization/autoware_ndt_scan_matcher/src/ndt_scan_matcher_core.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,7 @@ using autoware::localization_util::pose_to_matrix4f;
5151

5252
using autoware::localization_util::SmartPoseBuffer;
5353
using autoware::localization_util::TreeStructuredParzenEstimator;
54-
using autoware::universe_utils::DiagnosticInterface;
54+
using autoware::universe_utils::DiagnosticsInterface;
5555

5656
tier4_debug_msgs::msg::Float32Stamped make_float32_stamped(
5757
const builtin_interfaces::msg::Time & stamp, const float data)
@@ -141,7 +141,7 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options)
141141
std::make_unique<SmartPoseBuffer>(this->get_logger(), value_as_unlimited, value_as_unlimited);
142142

143143
diagnostics_regularization_pose_ =
144-
std::make_unique<DiagnosticInterface>(this, "regularization_pose_subscriber_status");
144+
std::make_unique<DiagnosticsInterface>(this, "regularization_pose_subscriber_status");
145145
}
146146

147147
sensor_aligned_pose_pub_ =
@@ -209,13 +209,13 @@ NDTScanMatcher::NDTScanMatcher(const rclcpp::NodeOptions & options)
209209
map_update_module_ =
210210
std::make_unique<MapUpdateModule>(this, &ndt_ptr_mtx_, ndt_ptr_, param_.dynamic_map_loading);
211211

212-
diagnostics_scan_points_ = std::make_unique<DiagnosticInterface>(this, "scan_matching_status");
212+
diagnostics_scan_points_ = std::make_unique<DiagnosticsInterface>(this, "scan_matching_status");
213213
diagnostics_initial_pose_ =
214-
std::make_unique<DiagnosticInterface>(this, "initial_pose_subscriber_status");
215-
diagnostics_map_update_ = std::make_unique<DiagnosticInterface>(this, "map_update_status");
216-
diagnostics_ndt_align_ = std::make_unique<DiagnosticInterface>(this, "ndt_align_service_status");
214+
std::make_unique<DiagnosticsInterface>(this, "initial_pose_subscriber_status");
215+
diagnostics_map_update_ = std::make_unique<DiagnosticsInterface>(this, "map_update_status");
216+
diagnostics_ndt_align_ = std::make_unique<DiagnosticsInterface>(this, "ndt_align_service_status");
217217
diagnostics_trigger_node_ =
218-
std::make_unique<DiagnosticInterface>(this, "trigger_node_service_status");
218+
std::make_unique<DiagnosticsInterface>(this, "trigger_node_service_status");
219219

220220
logger_configure_ = std::make_unique<autoware::universe_utils::LoggerLevelConfigure>(this);
221221
}

localization/autoware_pose_initializer/src/pose_initializer_core.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options)
4040
output_pose_covariance_ = get_covariance_parameter(this, "output_pose_covariance");
4141
gnss_particle_covariance_ = get_covariance_parameter(this, "gnss_particle_covariance");
4242

43-
diagnostics_pose_reliable_ = std::make_unique<autoware::universe_utils::DiagnosticInterface>(
43+
diagnostics_pose_reliable_ = std::make_unique<autoware::universe_utils::DiagnosticsInterface>(
4444
this, "pose_initializer_status");
4545

4646
if (declare_parameter<bool>("ekf_enabled")) {

localization/autoware_pose_initializer/src/pose_initializer_core.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ class PoseInitializer : public rclcpp::Node
6060
std::unique_ptr<EkfLocalizationTriggerModule> ekf_localization_trigger_;
6161
std::unique_ptr<NdtLocalizationTriggerModule> ndt_localization_trigger_;
6262
std::unique_ptr<autoware::universe_utils::LoggerLevelConfigure> logger_configure_;
63-
std::unique_ptr<autoware::universe_utils::DiagnosticInterface> diagnostics_pose_reliable_;
63+
std::unique_ptr<autoware::universe_utils::DiagnosticsInterface> diagnostics_pose_reliable_;
6464
double stop_check_duration_;
6565

6666
void change_node_trigger(bool flag, bool need_spin = false);

0 commit comments

Comments
 (0)