// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #include #include #include "rclcpp/rclcpp.hpp" #include "rclcpp/subscription_options.hpp" #include "std_msgs/msg/string.hpp" class MinimalSubscriberWithTopicStatistics : public rclcpp::Node { public: MinimalSubscriberWithTopicStatistics() : Node("minimal_subscriber_with_topic_statistics") { // manually enable topic statistics via options auto options = rclcpp::SubscriptionOptions(); options.topic_stats_options.state = rclcpp::TopicStatisticsState::Enable; // configure the collection window and publish period (default 1s) options.topic_stats_options.publish_period = std::chrono::seconds(10); // configure the topic name (default '/statistics') // options.topic_stats_options.publish_topic = "/topic_statistics" auto callback = [this](const std_msgs::msg::String & msg) { this->topic_callback(msg); }; subscription_ = this->create_subscription( "topic", 10, callback, options); } private: void topic_callback(const std_msgs::msg::String & msg) const { RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str()); } rclcpp::Subscription::SharedPtr subscription_; }; int main(int argc, char * argv[]) { rclcpp::init(argc, argv); rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; }