Skip to content

Commit

Permalink
Improved test_subscription_options (#1358)
Browse files Browse the repository at this point in the history
* Improved test_subscription_options

Signed-off-by: ahcorde <ahcorde@gmail.com>

* used RCLCPP_EXPECT_THROW_EQ in test_subcription_options

Signed-off-by: ahcorde <ahcorde@gmail.com>

* make linters happy

Signed-off-by: ahcorde <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Sep 30, 2020
1 parent bd214d3 commit 677af44
Showing 1 changed file with 15 additions and 0 deletions.
15 changes: 15 additions & 0 deletions rclcpp/test/rclcpp/test_subscription_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@
#include "rclcpp/node_options.hpp"
#include "rclcpp/subscription_options.hpp"

#include "../utils/rclcpp_gtest_macros.hpp"

using namespace std::chrono_literals;

namespace
Expand Down Expand Up @@ -85,4 +87,17 @@ TEST_F(TestSubscriptionOptions, topic_statistics_options_node_default_mode) {
rclcpp::detail::resolve_enable_topic_statistics(
subscription_options,
*(node->get_node_base_interface())));

subscription_options.topic_stats_options.state = rclcpp::TopicStatisticsState::Disable;
EXPECT_FALSE(
rclcpp::detail::resolve_enable_topic_statistics(
subscription_options,
*(node->get_node_base_interface())));

subscription_options.topic_stats_options.state = static_cast<rclcpp::TopicStatisticsState>(5);
RCLCPP_EXPECT_THROW_EQ(
rclcpp::detail::resolve_enable_topic_statistics(
subscription_options,
*(node->get_node_base_interface())),
std::runtime_error("Unrecognized EnableTopicStatistics value"));
}

0 comments on commit 677af44

Please sign in to comment.