Skip to content

Commit a9a0b7f

Browse files
feat(pointcloud preprocessor): add hysteresis to diag (#1309)
* remove diagnostics_updater * add counter * change node name * rename * style(pre-commit): autofix --------- Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent afc4fd4 commit a9a0b7f

File tree

3 files changed

+44
-19
lines changed

3 files changed

+44
-19
lines changed

launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -435,7 +435,7 @@ def get_additional_lidars_concatenated_component(input_topics, output_topic):
435435
return ComposableNode(
436436
package="pointcloud_preprocessor",
437437
plugin="pointcloud_preprocessor::PointCloudConcatenationComponent",
438-
name="concatenate_data",
438+
name="concatenate_ground",
439439
remappings=[
440440
("output", output_topic),
441441
],

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

+5-3
Original file line numberDiff line numberDiff line change
@@ -63,11 +63,11 @@
6363
// ROS includes
6464
#include "autoware_point_types/types.hpp"
6565

66-
#include <diagnostic_updater/diagnostic_updater.hpp>
6766
#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>
6867
#include <tier4_autoware_utils/ros/debug_publisher.hpp>
6968
#include <tier4_autoware_utils/system/stop_watch.hpp>
7069

70+
#include <diagnostic_msgs/msg/diagnostic_array.hpp>
7171
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
7272
#include <geometry_msgs/msg/twist_stamped.hpp>
7373
#include <geometry_msgs/msg/twist_with_covariance_stamped.hpp>
@@ -138,7 +138,7 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
138138
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
139139

140140
rclcpp::TimerBase::SharedPtr timer_;
141-
diagnostic_updater::Updater updater_{this};
141+
rclcpp::Publisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr diagnostics_pub_;
142142

143143
const std::string input_twist_topic_type_;
144144

@@ -180,7 +180,9 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
180180
void odom_callback(const nav_msgs::msg::Odometry::ConstSharedPtr input);
181181
void timer_callback();
182182

183-
void checkConcatStatus(diagnostic_updater::DiagnosticStatusWrapper & stat);
183+
void checkConcatStatus();
184+
int consecutive_concatenate_failures{0};
185+
184186
std::string replaceSyncTopicNamePostfix(
185187
const std::string & original_topic_name, const std::string & postfix);
186188

sensing/pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp

+38-15
Original file line numberDiff line numberDiff line change
@@ -211,9 +211,8 @@ PointCloudConcatenateDataSynchronizerComponent::PointCloudConcatenateDataSynchro
211211

212212
// Diagnostic Updater
213213
{
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);
217216
}
218217
}
219218

@@ -463,7 +462,7 @@ void PointCloudConcatenateDataSynchronizerComponent::publish()
463462
}
464463
}
465464

466-
updater_.force_update();
465+
checkConcatStatus();
467466

468467
cloud_stdmap_ = cloud_stdmap_tmp_;
469468
std::for_each(std::begin(cloud_stdmap_tmp_), std::end(cloud_stdmap_tmp_), [](auto & e) {
@@ -684,21 +683,45 @@ void PointCloudConcatenateDataSynchronizerComponent::odom_callback(
684683
twist_ptr_queue_.push_back(twist_ptr);
685684
}
686685

687-
void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus(
688-
diagnostic_updater::DiagnosticStatusWrapper & stat)
686+
void PointCloudConcatenateDataSynchronizerComponent::checkConcatStatus()
689687
{
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+
690692
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;
693703
}
694704

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);
702725
}
703726
} // namespace pointcloud_preprocessor
704727

0 commit comments

Comments
 (0)