Skip to content

Commit

Permalink
Add check for invalid topic statistics publish period (ros2#1151)
Browse files Browse the repository at this point in the history
* Add check for invalid topic statistics publish period

Signed-off-by: Devin Bonnie <dbbonnie@amazon.com>

* Update documentation

Signed-off-by: Devin Bonnie <dbbonnie@amazon.com>

* Address review comments

Signed-off-by: Devin Bonnie <dbbonnie@amazon.com>

* Address doc formatting comments

Signed-off-by: Devin Bonnie <dbbonnie@amazon.com>

* Update doc spacing

Signed-off-by: Devin Bonnie <dbbonnie@amazon.com>
  • Loading branch information
dabonnie committed Jun 11, 2020
1 parent bf70ce1 commit a621c4a
Show file tree
Hide file tree
Showing 3 changed files with 52 additions and 1 deletion.
25 changes: 25 additions & 0 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <chrono>
#include <functional>
#include <memory>
#include <stdexcept>
#include <string>
#include <utility>

Expand All @@ -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,
Expand Down Expand Up @@ -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<statistics_msgs::msg::MetricsMessage>> publisher =
create_publisher<statistics_msgs::msg::MetricsMessage>(
node,
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/subscription_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)};
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <iostream>
#include <memory>
#include <set>
#include <stdexcept>
#include <string>
#include <vector>

Expand Down Expand Up @@ -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<rclcpp::Node>("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<Empty, std::function<void(Empty::UniquePtr)>>(
"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<EmptySubscriber>(
Expand Down

0 comments on commit a621c4a

Please sign in to comment.