@@ -211,9 +211,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
211
211
212
212
// Diagnostic Updater
213
213
{
214
- updater_.setHardwareID (" concatenate_data_checker" );
215
- updater_.add (
216
- " concat_status" , this , &PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus);
214
+ diagnostics_pub_ =
215
+ this ->create_publisher <diagnostic_msgs::msg::DiagnosticArray>(" /diagnostics" , 10 );
217
216
}
218
217
}
219
218
@@ -463,7 +462,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publish()
463
462
}
464
463
}
465
464
466
- updater_. force_update ();
465
+ checkConcatStatus ();
467
466
468
467
cloud_stdmap_ = cloud_stdmap_tmp_;
469
468
std::for_each (std::begin (cloud_stdmap_tmp_), std::end (cloud_stdmap_tmp_), [](auto & e) {
@@ -684,21 +683,45 @@ void PointCloudConcatenateDataSynchronizerComponent::odom_callback(
684
683
twist_ptr_queue_.push_back (twist_ptr);
685
684
}
686
685
687
- void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus (
688
- diagnostic_updater::DiagnosticStatusWrapper & stat)
686
+ void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus ()
689
687
{
688
+ diagnostic_msgs::msg::DiagnosticStatus diag_status_msg;
689
+ diag_status_msg.name = std::string (this ->get_name ()) + " : concat_status" ;
690
+ diag_status_msg.hardware_id = " concatenate_data_checker" ;
691
+
690
692
for (const std::string & e : input_topics_) {
691
- const std::string subscribe_status = not_subscribed_topic_names_.count (e) ? " NG" : " OK" ;
692
- stat.add (e, subscribe_status);
693
+ diagnostic_msgs::msg::KeyValue key_value_msg;
694
+ key_value_msg.key = e;
695
+ key_value_msg.value = not_subscribed_topic_names_.count (e) ? " NG" : " OK" ;
696
+ diag_status_msg.values .push_back (key_value_msg);
697
+ }
698
+
699
+ if (not_subscribed_topic_names_.size () > 0 ) {
700
+ consecutive_concatenate_failures += 1 ;
701
+ } else {
702
+ consecutive_concatenate_failures = 0 ;
693
703
}
694
704
695
- const int8_t level = not_subscribed_topic_names_.empty ()
696
- ? diagnostic_msgs::msg::DiagnosticStatus::OK
697
- : diagnostic_msgs::msg::DiagnosticStatus::WARN;
698
- const std::string message = not_subscribed_topic_names_.empty ()
699
- ? " Concatenate all topics"
700
- : " Some topics are not concatenated" ;
701
- stat.summary (level, message);
705
+ {
706
+ diagnostic_msgs::msg::KeyValue key_value_msg;
707
+ key_value_msg.key = " consecutiveConcatenateFailures" ;
708
+ key_value_msg.value = std::to_string (consecutive_concatenate_failures_);
709
+ diag_status_msg.values .push_back (key_value_msg);
710
+ }
711
+
712
+ if (consecutive_concatenate_failures > 1 ) {
713
+ diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::WARN;
714
+ diag_status_msg.message = " Some topics are not concatenated" ;
715
+ } else {
716
+ diag_status_msg.level = diagnostic_msgs::msg::DiagnosticStatus::OK;
717
+ diag_status_msg.message = " Concatenate all topics" ;
718
+ }
719
+
720
+ diagnostic_msgs::msg::DiagnosticArray diag_msg;
721
+ diag_msg.header .stamp = this ->now ();
722
+ diag_msg.status .push_back (diag_status_msg);
723
+
724
+ diagnostics_pub_->publish (diag_msg);
702
725
}
703
726
} // namespace pointcloud_preprocessor
704
727
0 commit comments