From 77564eb2ff1c92157af2fa32e6947a03a0f3e70e Mon Sep 17 00:00:00 2001 From: Devin Bonnie <47613035+dabonnie@users.noreply.github.com> Date: Mon, 15 Jun 2020 10:25:17 -0700 Subject: [PATCH] Add check for invalid topic statistics publish period (#1151) (#1172) * Add check for invalid topic statistics publish period Signed-off-by: Devin Bonnie * Update documentation Signed-off-by: Devin Bonnie * Address review comments Signed-off-by: Devin Bonnie * Address doc formatting comments Signed-off-by: Devin Bonnie * Update doc spacing Signed-off-by: Devin Bonnie --- rclcpp/include/rclcpp/create_subscription.hpp | 25 +++++++++++++++++++ .../include/rclcpp/subscription_options.hpp | 3 ++- .../test_subscription_topic_statistics.cpp | 25 +++++++++++++++++++ 3 files changed, 52 insertions(+), 1 deletion(-) diff --git a/rclcpp/include/rclcpp/create_subscription.hpp b/rclcpp/include/rclcpp/create_subscription.hpp index 207bee4a71..2eb24b48b5 100644 --- a/rclcpp/include/rclcpp/create_subscription.hpp +++ b/rclcpp/include/rclcpp/create_subscription.hpp @@ -18,6 +18,7 @@ #include #include #include +#include #include #include @@ -44,6 +45,23 @@ namespace rclcpp * The NodeT type only needs to have a method called get_node_topics_interface() * which returns a shared_ptr to a NodeTopicsInterface, or be a * NodeTopicsInterface pointer itself. + * + * \tparam MessageT + * \tparam CallbackT + * \tparam AllocatorT + * \tparam CallbackMessageT + * \tparam SubscriptionT + * \tparam MessageMemoryStrategyT + * \tparam NodeT + * \param node + * \param topic_name + * \param qos + * \param callback + * \param options + * \param msg_mem_strat + * \return the created subscription + * \throws std::invalid_argument if topic statistics is enabled and the publish period is + * less than or equal to zero. */ template< typename MessageT, @@ -81,6 +99,13 @@ create_subscription( options, *node_topics->get_node_base_interface())) { + if (options.topic_stats_options.publish_period <= std::chrono::milliseconds(0)) { + throw std::invalid_argument( + "topic_stats_options.publish_period must be greater than 0, specified value of " + + std::to_string(options.topic_stats_options.publish_period.count()) + + " ms"); + } + std::shared_ptr> publisher = create_publisher( node, diff --git a/rclcpp/include/rclcpp/subscription_options.hpp b/rclcpp/include/rclcpp/subscription_options.hpp index 5088f35fb1..ebf4331c4f 100644 --- a/rclcpp/include/rclcpp/subscription_options.hpp +++ b/rclcpp/include/rclcpp/subscription_options.hpp @@ -66,7 +66,8 @@ struct SubscriptionOptionsBase // Topic to which topic statistics get published when enabled. Defaults to /statistics. std::string publish_topic = "/statistics"; - // Topic statistics publication period in ms. Defaults to one minute. + // Topic statistics publication period in ms. Defaults to one second. + // Only values greater than zero are allowed. std::chrono::milliseconds publish_period{std::chrono::seconds(1)}; }; diff --git a/rclcpp/test/topic_statistics/test_subscription_topic_statistics.cpp b/rclcpp/test/topic_statistics/test_subscription_topic_statistics.cpp index 74a79e6f9b..dc4e1fa86e 100644 --- a/rclcpp/test/topic_statistics/test_subscription_topic_statistics.cpp +++ b/rclcpp/test/topic_statistics/test_subscription_topic_statistics.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include #include @@ -219,6 +220,30 @@ class TestSubscriptionTopicStatisticsFixture : public ::testing::Test } }; +TEST(TestSubscriptionTopicStatistics, test_invalid_publish_period) +{ + rclcpp::init(0 /* argc */, nullptr /* argv */); + + auto node = std::make_shared("test_period_node"); + + auto options = rclcpp::SubscriptionOptions(); + options.topic_stats_options.state = rclcpp::TopicStatisticsState::Enable; + options.topic_stats_options.publish_period = std::chrono::milliseconds(0); + + auto callback = [](Empty::UniquePtr msg) { + (void) msg; + }; + + ASSERT_THROW( + (node->create_subscription>( + "should_throw_invalid_arg", + rclcpp::QoS(rclcpp::KeepAll()), + callback, + options)), std::invalid_argument); + + rclcpp::shutdown(); +} + TEST_F(TestSubscriptionTopicStatisticsFixture, test_manual_construction) { auto empty_subscriber = std::make_shared(