diff --git a/rclcpp/test/rclcpp/test_publisher_subscription_count_api.cpp b/rclcpp/test/rclcpp/test_publisher_subscription_count_api.cpp index cbcd4f12ed..0a59ebe100 100644 --- a/rclcpp/test/rclcpp/test_publisher_subscription_count_api.cpp +++ b/rclcpp/test/rclcpp/test_publisher_subscription_count_api.cpp @@ -24,27 +24,92 @@ #include "test_msgs/msg/empty.hpp" -using test_msgs::msg::Empty; +namespace +{ -/** - * Parameterized test. - * The first param are the NodeOptions used to create the nodes. - * The second param are the expect intraprocess count results. - */ -struct TestParameters + +template +class NodeCreationPolicy { - rclcpp::NodeOptions node_options[2]; - uint64_t intraprocess_count_results[2]; - std::string description; +public: + rclcpp::NodeOptions & node_options() + { + return options_; + } + +private: + rclcpp::NodeOptions options_; }; -std::ostream & operator<<(std::ostream & out, const TestParameters & params) +template +class NodeCreationPolicy { - out << params.description; - return out; -} +public: + NodeCreationPolicy() + { + gather(options_); + } + + rclcpp::NodeOptions & node_options() + { + return options_; + } + +private: + template + static rclcpp::NodeOptions & + gather(rclcpp::NodeOptions & options) + { + return U::gather(options); + } + + template + static rclcpp::NodeOptions & + gather(rclcpp::NodeOptions & options) + { + return gather(U::gather(options)); + } + + rclcpp::NodeOptions options_; +}; + +template +struct ShouldUseIntraprocess +{ + static rclcpp::NodeOptions & gather(rclcpp::NodeOptions & options) + { + return options.use_intra_process_comms(value); + } +}; + +using UseIntraprocess = ShouldUseIntraprocess; +using DoNotUseIntraprocess = ShouldUseIntraprocess; + +struct UseCustomContext +{ + static rclcpp::NodeOptions & gather(rclcpp::NodeOptions & options) + { + auto context = rclcpp::Context::make_shared(); + context->init(0, nullptr); + return options.context(context); + } +}; -class TestPublisherSubscriptionCount : public ::testing::TestWithParam +struct PrintTestDescription +{ + template + static std::string GetName(int i) + { + static_cast(i); + return T::description; + } +}; + +} // namespace + + +template +class TestPublisherSubscriptionCount : public ::testing::Test { public: static void SetUpTestCase() @@ -57,126 +122,128 @@ class TestPublisherSubscriptionCount : public ::testing::TestWithParam; + using SecondNodeCreationPolicy = NodeCreationPolicy; - static std::chrono::milliseconds offset; + static constexpr bool first_node_talks_intraprocess{true}; + static constexpr bool both_nodes_talk_intraprocess{true}; }; -std::chrono::milliseconds TestPublisherSubscriptionCount::offset = std::chrono::milliseconds(2000); +/* Testing publisher subscription count api and internal process subscription count. + * Two subscriptions, one using intra-process comm and the other not using it. + */ +struct TwoSubscriptionsOneIntraprocessOneNot +{ + static constexpr const char * description = + "two_subscriptions_one_intraprocess_one_not"; + using FirstNodeCreationPolicy = NodeCreationPolicy; + using SecondNodeCreationPolicy = NodeCreationPolicy<>; + + static constexpr bool first_node_talks_intraprocess{true}; + static constexpr bool both_nodes_talk_intraprocess{false}; +}; -void OnMessage(const test_msgs::msg::Empty::SharedPtr msg) +/* Testing publisher subscription count api and internal process subscription count. + * Two contexts, both using intra-process. + */ +struct TwoSubscriptionsInTwoContextsWithIntraprocessComm { - (void)msg; -} + static constexpr const char * description = + "two_subscriptions_in_two_contexts_with_intraprocess_comm"; + using FirstNodeCreationPolicy = NodeCreationPolicy; + using SecondNodeCreationPolicy = NodeCreationPolicy; + + static constexpr bool first_node_talks_intraprocess{true}; + static constexpr bool both_nodes_talk_intraprocess{false}; +}; -TEST_P(TestPublisherSubscriptionCount, increasing_and_decreasing_counts) +/* Testing publisher subscription count api and internal process subscription count. + * Two contexts, both of them not using intra-process comm. + */ +struct TwoSubscriptionsInTwoContextsWithoutIntraprocessComm { - TestParameters parameters = GetParam(); + static constexpr const char * description = + "two_subscriptions_in_two_contexts_without_intraprocess_comm"; + using FirstNodeCreationPolicy = NodeCreationPolicy<>; + using SecondNodeCreationPolicy = NodeCreationPolicy; + + static constexpr bool first_node_talks_intraprocess{false}; + static constexpr bool both_nodes_talk_intraprocess{false}; +}; + +using AllTestDescriptions = ::testing::Types< + TwoSubscriptionsIntraprocessComm, + TwoSubscriptionsOneIntraprocessOneNot, + TwoSubscriptionsInTwoContextsWithIntraprocessComm, + TwoSubscriptionsInTwoContextsWithoutIntraprocessComm +>; +TYPED_TEST_CASE(TestPublisherSubscriptionCount, AllTestDescriptions, PrintTestDescription); + + +using test_msgs::msg::Empty; + +TYPED_TEST(TestPublisherSubscriptionCount, increasing_and_decreasing_counts) +{ + using TestDescription = TypeParam; + typename TestDescription::FirstNodeCreationPolicy my_node_creation_policy; rclcpp::Node::SharedPtr node = std::make_shared( "my_node", "/ns", - parameters.node_options[0]); + my_node_creation_policy.node_options()); auto publisher = node->create_publisher("/topic", 10); EXPECT_EQ(publisher->get_subscription_count(), 0u); EXPECT_EQ(publisher->get_intra_process_subscription_count(), 0u); { - auto sub = node->create_subscription("/topic", 10, &OnMessage); - rclcpp::sleep_for(offset); + auto sub = node->create_subscription( + "/topic", 10, &TestPublisherSubscriptionCount::OnMessage); + rclcpp::sleep_for(this->offset); EXPECT_EQ(publisher->get_subscription_count(), 1u); EXPECT_EQ( publisher->get_intra_process_subscription_count(), - parameters.intraprocess_count_results[0]); + (TestDescription::first_node_talks_intraprocess ? 1u : 0u)); { + typename TestDescription::SecondNodeCreationPolicy another_node_creation_policy; rclcpp::Node::SharedPtr another_node = std::make_shared( "another_node", "/ns", - parameters.node_options[1]); - auto another_sub = - another_node->create_subscription("/topic", 10, &OnMessage); + another_node_creation_policy.node_options()); + auto another_sub = another_node->create_subscription( + "/topic", 10, &TestPublisherSubscriptionCount::OnMessage); - rclcpp::sleep_for(offset); + rclcpp::sleep_for(this->offset); EXPECT_EQ(publisher->get_subscription_count(), 2u); EXPECT_EQ( publisher->get_intra_process_subscription_count(), - parameters.intraprocess_count_results[1]); + (TestDescription::first_node_talks_intraprocess ? 1u : 0u) + + (TestDescription::both_nodes_talk_intraprocess ? 1u : 0u)); } - rclcpp::sleep_for(offset); + rclcpp::sleep_for(this->offset); EXPECT_EQ(publisher->get_subscription_count(), 1u); EXPECT_EQ( publisher->get_intra_process_subscription_count(), - parameters.intraprocess_count_results[0]); + (TestDescription::first_node_talks_intraprocess ? 1u : 0u)); } /** * Counts should be zero here, as all are subscriptions are out of scope. * Subscriptions count checking is always preceeded with an sleep, as random failures had been * detected without it. */ - rclcpp::sleep_for(offset); + rclcpp::sleep_for(this->offset); EXPECT_EQ(publisher->get_subscription_count(), 0u); EXPECT_EQ(publisher->get_intra_process_subscription_count(), 0u); } - -auto get_new_context() -{ - auto context = rclcpp::Context::make_shared(); - context->init(0, nullptr); - return context; -} - -TestParameters parameters[] = { - /* - Testing publisher subscription count api and internal process subscription count. - Two subscriptions in the same topic, both using intraprocess comm. - */ - { - { - rclcpp::NodeOptions().use_intra_process_comms(true), - rclcpp::NodeOptions().use_intra_process_comms(true) - }, - {1u, 2u}, - "two_subscriptions_intraprocess_comm" - }, - /* - Testing publisher subscription count api and internal process subscription count. - Two subscriptions, one using intra-process comm and the other not using it. - */ - { - { - rclcpp::NodeOptions().use_intra_process_comms(true), - rclcpp::NodeOptions().use_intra_process_comms(false) - }, - {1u, 1u}, - "two_subscriptions_one_intraprocess_one_not" - }, - /* - Testing publisher subscription count api and internal process subscription count. - Two contexts, both using intra-process. - */ - { - { - rclcpp::NodeOptions().use_intra_process_comms(true), - rclcpp::NodeOptions().context(get_new_context()).use_intra_process_comms(true) - }, - {1u, 1u}, - "two_subscriptions_in_two_contexts_with_intraprocess_comm" - }, - /* - Testing publisher subscription count api and internal process subscription count. - Two contexts, both of them not using intra-process comm. - */ - { - { - rclcpp::NodeOptions().use_intra_process_comms(false), - rclcpp::NodeOptions().context(get_new_context()).use_intra_process_comms(false) - }, - {0u, 0u}, - "two_subscriptions_in_two_contexts_without_intraprocess_comm" - } -}; - -INSTANTIATE_TEST_CASE_P( - TestWithDifferentNodeOptions, TestPublisherSubscriptionCount, - ::testing::ValuesIn(parameters), - ::testing::PrintToStringParamName()); diff --git a/rclcpp/test/rclcpp/test_subscription_publisher_count_api.cpp b/rclcpp/test/rclcpp/test_subscription_publisher_count_api.cpp index e79b332a03..8da31f3060 100644 --- a/rclcpp/test/rclcpp/test_subscription_publisher_count_api.cpp +++ b/rclcpp/test/rclcpp/test_subscription_publisher_count_api.cpp @@ -1,4 +1,4 @@ -// Copyright 2019 Open Source Robotics Foundation, Inc. +// Copyright 2019-2020 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -23,21 +23,79 @@ #include "test_msgs/msg/empty.hpp" -using test_msgs::msg::Empty; +namespace +{ -struct TestParameters +template +class NodeCreationPolicy { - rclcpp::NodeOptions node_options; - std::string description; +public: + rclcpp::NodeOptions & node_options() + { + return options_; + } + +private: + rclcpp::NodeOptions options_; }; -std::ostream & operator<<(std::ostream & out, const TestParameters & params) +template +class NodeCreationPolicy { - out << params.description; - return out; -} +public: + NodeCreationPolicy() + { + gather(options_); + } -class TestSubscriptionPublisherCount : public ::testing::TestWithParam + rclcpp::NodeOptions & node_options() + { + return options_; + } + +private: + template + static rclcpp::NodeOptions & + gather(rclcpp::NodeOptions & options) + { + return U::gather(options); + } + + template + static rclcpp::NodeOptions & + gather(rclcpp::NodeOptions & options) + { + return gather(U::gather(options)); + } + + rclcpp::NodeOptions options_; +}; + +struct UseCustomContext +{ + static rclcpp::NodeOptions & gather(rclcpp::NodeOptions & options) + { + auto context = rclcpp::Context::make_shared(); + context->init(0, nullptr); + return options.context(context); + } +}; + +struct PrintTestDescription +{ + template + static std::string GetName(int i) + { + static_cast(i); + return T::description; + } +}; + +} // namespace + + +template +class TestSubscriptionPublisherCount : public ::testing::Test { public: static void SetUpTestCase() @@ -50,78 +108,59 @@ class TestSubscriptionPublisherCount : public ::testing::TestWithParam; +}; -void OnMessage(const test_msgs::msg::Empty::SharedPtr msg) +struct TwoContextsPerTest { - (void)msg; -} + static constexpr const char * description = "two_contexts_test"; + using NodeCreationPolicy = ::NodeCreationPolicy; +}; -TEST_P(TestSubscriptionPublisherCount, increasing_and_decreasing_counts) +using AllTestDescriptions = ::testing::Types; +TYPED_TEST_CASE(TestSubscriptionPublisherCount, AllTestDescriptions, PrintTestDescription); + + +using test_msgs::msg::Empty; + +TYPED_TEST(TestSubscriptionPublisherCount, increasing_and_decreasing_counts) { - rclcpp::NodeOptions node_options = GetParam().node_options; - rclcpp::Node::SharedPtr node = std::make_shared( - "my_node", - "/ns", - node_options); - auto subscription = node->create_subscription("/topic", 10, &OnMessage); + using TestDescription = TypeParam; + rclcpp::Node::SharedPtr node = std::make_shared("my_node", "/ns"); + auto subscription = node->create_subscription( + "/topic", 10, &TestSubscriptionPublisherCount::OnMessage); EXPECT_EQ(subscription->get_publisher_count(), 0u); { auto pub = node->create_publisher("/topic", 10); - rclcpp::sleep_for(offset); + rclcpp::sleep_for(this->offset); EXPECT_EQ(subscription->get_publisher_count(), 1u); { + typename TestDescription::NodeCreationPolicy node_creation_policy; rclcpp::Node::SharedPtr another_node = std::make_shared( "another_node", "/ns", - node_options); + node_creation_policy.node_options()); auto another_pub = another_node->create_publisher("/topic", 10); - rclcpp::sleep_for(offset); + rclcpp::sleep_for(this->offset); EXPECT_EQ(subscription->get_publisher_count(), 2u); } - rclcpp::sleep_for(offset); + rclcpp::sleep_for(this->offset); EXPECT_EQ(subscription->get_publisher_count(), 1u); } - rclcpp::sleep_for(offset); + rclcpp::sleep_for(this->offset); EXPECT_EQ(subscription->get_publisher_count(), 0u); } - -auto get_new_context() -{ - auto context = rclcpp::Context::make_shared(); - context->init(0, nullptr); - return context; -} - -TestParameters parameters[] = { - /* - Testing subscription publisher count api. - One context. - */ - { - rclcpp::NodeOptions(), - "one_context_test" - }, - /* - Testing subscription publisher count api. - Two contexts. - */ - { - rclcpp::NodeOptions().context(get_new_context()), - "two_contexts_test" - } -}; - -INSTANTIATE_TEST_CASE_P( - TestWithDifferentNodeOptions, - TestSubscriptionPublisherCount, - testing::ValuesIn(parameters), - testing::PrintToStringParamName());