Add check for invalid topic statistics publish period (#1151) (#1172)

* 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>
This commit is contained in:
Devin Bonnie 2020-06-15 10:25:17 -07:00 committed by GitHub
parent bf70ce15bf
commit 77564eb2ff
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
3 changed files with 52 additions and 1 deletions

View file

@ -18,6 +18,7 @@
#include <chrono> #include <chrono>
#include <functional> #include <functional>
#include <memory> #include <memory>
#include <stdexcept>
#include <string> #include <string>
#include <utility> #include <utility>
@ -44,6 +45,23 @@ namespace rclcpp
* The NodeT type only needs to have a method called get_node_topics_interface() * 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 * which returns a shared_ptr to a NodeTopicsInterface, or be a
* NodeTopicsInterface pointer itself. * 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< template<
typename MessageT, typename MessageT,
@ -81,6 +99,13 @@ create_subscription(
options, options,
*node_topics->get_node_base_interface())) *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 = std::shared_ptr<Publisher<statistics_msgs::msg::MetricsMessage>> publisher =
create_publisher<statistics_msgs::msg::MetricsMessage>( create_publisher<statistics_msgs::msg::MetricsMessage>(
node, node,

View file

@ -66,7 +66,8 @@ struct SubscriptionOptionsBase
// Topic to which topic statistics get published when enabled. Defaults to /statistics. // Topic to which topic statistics get published when enabled. Defaults to /statistics.
std::string publish_topic = "/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)}; std::chrono::milliseconds publish_period{std::chrono::seconds(1)};
}; };

View file

@ -19,6 +19,7 @@
#include <iostream> #include <iostream>
#include <memory> #include <memory>
#include <set> #include <set>
#include <stdexcept>
#include <string> #include <string>
#include <vector> #include <vector>
@ -219,6 +220,30 @@ protected:
} }
}; };
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) TEST_F(TestSubscriptionTopicStatisticsFixture, test_manual_construction)
{ {
auto empty_subscriber = std::make_shared<EmptySubscriber>( auto empty_subscriber = std::make_shared<EmptySubscriber>(