From 0656ecf0c87f0883eaea757ee9ede729a8002ac4 Mon Sep 17 00:00:00 2001 From: Shinnosuke Hirakawa Date: Thu, 23 May 2024 15:57:01 +0900 Subject: [PATCH] rename --- .../concatenate_and_time_sync_nodelet.hpp | 2 +- .../concatenate_and_time_sync_nodelet.cpp | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp index 9b5d8a72ee426..a4522da2bf7b4 100644 --- a/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ b/sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp @@ -181,7 +181,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node void timer_callback(); void checkConcatStatus(); - int concat_miss_count_{0}; + int consecutive_concatenate_failures{0}; std::string replaceSyncTopicNamePostfix( const std::string & original_topic_name, const std::string & postfix); diff --git a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index 2c848f75b0b6a..d4fe19b783ba9 100644 --- a/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -697,19 +697,19 @@ void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus() } if(not_subscribed_topic_names_.size() > 0) { - concat_miss_count_ += 1; + consecutive_concatenate_failures += 1; }else{ - concat_miss_count_ = 0; + consecutive_concatenate_failures = 0; } { diagnostic_msgs::msg::KeyValue key_value_msg; - key_value_msg.key = "miss_count"; - key_value_msg.value = std::to_string(concat_miss_count_); + key_value_msg.key = "consecutiveConcatenateFailures"; + key_value_msg.value = std::to_string(consecutive_concatenate_failures_); diag_status_msg.values.push_back(key_value_msg); } - if(concat_miss_count_ > 2){ + if(consecutive_concatenate_failures > 1){ diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN; diag_status_msg.message = "Some topics are not concatenated"; }else{