Subscribing to topic statistics within node calculating them

asked 2023-06-05 13:17:27 -0600

dhood gravatar image

I am interested in monitoring a publisher from another node to take some action if it stops publishing. There are different ways to achieve this, but I thought I'd take advantage of Topic Statistics doing the calculation for me.

The SubscriptionTopicStatisticsSharedPtr from the subscription is private, so I am trying to analyse the Topic Statistics message that is being published, by subscribing to it again.

I have enabled intra process communication but it still doesn't work how I expect. I can appreciate this is might be an edge case as far as the Node is concerned (you don't normally subscribe to yourself), but as for a use case.. it seems reasonable that the node generating the Topic Statistics might also want to access the content. (Am I the first..?)

Any ideas if this should/shouldn't work? (Code based off https://docs.ros.org/en/humble/Tutori..., with statistics_msgs dependency added in CMakeLists)

#include <chrono>
#include <memory>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/subscription_options.hpp"

#include "std_msgs/msg/string.hpp"
#include "statistics_msgs/msg/metrics_message.hpp"

class TalkerMonitor : public rclcpp::Node
{
public:
  TalkerMonitor()
  : Node("talker_monitor", rclcpp::NodeOptions().use_intra_process_comms(true))
  {
    // Enable topic statistics so we can notice when the cicada stops publishing
    auto options = rclcpp::SubscriptionOptions();
    options.topic_stats_options.state = rclcpp::TopicStatisticsState::Enable;
    options.topic_stats_options.publish_period = std::chrono::seconds(1);

    options.topic_stats_options.publish_topic = "/topic_statistics";

    auto callback = [this](std_msgs::msg::String::SharedPtr msg) {
        this->topic_callback(msg);
      };

    subscription_ = this->create_subscription<std_msgs::msg::String>(
      "topic", 10, callback, options);

    auto callback2 = [this](statistics_msgs::msg::MetricsMessage msg) {
        this->topic_callback2(msg);
      };

    statistics_subscription_ = this->create_subscription<statistics_msgs::msg::MetricsMessage>(
      "/cicada_frame_topic_statistics", 10, callback2);
  }

private:
  void topic_callback(const std_msgs::msg::String::ConstSharedPtr msg) const
  {
    RCLCPP_INFO(this->get_logger(), "Received topic message.");
  }
  void topic_callback2(const statistics_msgs::msg::MetricsMessage msg) const
  {
    RCLCPP_INFO(this->get_logger(), "Received statistics message.");
  }
  rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
  rclcpp::Subscription<statistics_msgs::msg::MetricsMessage>::SharedPtr statistics_subscription_;
};

int main(int argc, char * argv[])
{
  rclcpp::init(argc, argv);
  rclcpp::spin(std::make_shared<TalkerMonitor>());
  rclcpp::shutdown();
  return 0;
}

I can echo the statics topic from the command line, but get this unexpected behaviour with 0 subscribers:

$ ros2 topic info /topic_statistics
Type: statistics_msgs/msg/MetricsMessage
Publisher count: 1
Subscription count: 0
edit retag flag offensive close merge delete