Skip to content

Commit 0656ecf

Browse files
committed
rename
1 parent 58e4781 commit 0656ecf

File tree

2 files changed

+6
-6
lines changed

2 files changed

+6
-6
lines changed

sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -181,7 +181,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
181181
void timer_callback();
182182

183183
void checkConcatStatus();
184-
int concat_miss_count_{0};
184+
int consecutive_concatenate_failures{0};
185185

186186
std::string replaceSyncTopicNamePostfix(
187187
const std::string & original_topic_name, const std::string & postfix);

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -697,19 +697,19 @@ void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus()
697697
}
698698

699699
if(not_subscribed_topic_names_.size() > 0) {
700-
concat_miss_count_ += 1;
700+
consecutive_concatenate_failures += 1;
701701
}else{
702-
concat_miss_count_ = 0;
702+
consecutive_concatenate_failures = 0;
703703
}
704704

705705
{
706706
diagnostic_msgs::msg::KeyValue key_value_msg;
707-
key_value_msg.key = "miss_count";
708-
key_value_msg.value = std::to_string(concat_miss_count_);
707+
key_value_msg.key = "consecutiveConcatenateFailures";
708+
key_value_msg.value = std::to_string(consecutive_concatenate_failures_);
709709
diag_status_msg.values.push_back(key_value_msg);
710710
}
711711

712-
if(concat_miss_count_ > 2){
712+
if(consecutive_concatenate_failures > 1){
713713
diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
714714
diag_status_msg.message = "Some topics are not concatenated";
715715
}else{

0 commit comments

Comments
 (0)