Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com> Co-authored-by: Michel Hidalgo <michel@ekumenlabs.com>
This commit is contained in:
parent
8bfc8e631f
commit
b67fa594f8
2 changed files with 271 additions and 165 deletions
|
@ -24,27 +24,92 @@
|
||||||
|
|
||||||
#include "test_msgs/msg/empty.hpp"
|
#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
|
|
||||||
{
|
{
|
||||||
rclcpp::NodeOptions node_options[2];
|
|
||||||
uint64_t intraprocess_count_results[2];
|
|
||||||
std::string description;
|
template<typename ... Ts>
|
||||||
|
class NodeCreationPolicy
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
rclcpp::NodeOptions & node_options()
|
||||||
|
{
|
||||||
|
return options_;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
rclcpp::NodeOptions options_;
|
||||||
};
|
};
|
||||||
|
|
||||||
std::ostream & operator<<(std::ostream & out, const TestParameters & params)
|
template<typename T, typename ... Ts>
|
||||||
|
class NodeCreationPolicy<T, Ts...>
|
||||||
{
|
{
|
||||||
out << params.description;
|
public:
|
||||||
return out;
|
NodeCreationPolicy()
|
||||||
}
|
{
|
||||||
|
gather<T, Ts...>(options_);
|
||||||
|
}
|
||||||
|
|
||||||
class TestPublisherSubscriptionCount : public ::testing::TestWithParam<TestParameters>
|
rclcpp::NodeOptions & node_options()
|
||||||
|
{
|
||||||
|
return options_;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
template<typename U>
|
||||||
|
static rclcpp::NodeOptions &
|
||||||
|
gather(rclcpp::NodeOptions & options)
|
||||||
|
{
|
||||||
|
return U::gather(options);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename U, typename V, typename ... Ws>
|
||||||
|
static rclcpp::NodeOptions &
|
||||||
|
gather(rclcpp::NodeOptions & options)
|
||||||
|
{
|
||||||
|
return gather<V, Ws...>(U::gather(options));
|
||||||
|
}
|
||||||
|
|
||||||
|
rclcpp::NodeOptions options_;
|
||||||
|
};
|
||||||
|
|
||||||
|
template<bool value>
|
||||||
|
struct ShouldUseIntraprocess
|
||||||
|
{
|
||||||
|
static rclcpp::NodeOptions & gather(rclcpp::NodeOptions & options)
|
||||||
|
{
|
||||||
|
return options.use_intra_process_comms(value);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
using UseIntraprocess = ShouldUseIntraprocess<true>;
|
||||||
|
using DoNotUseIntraprocess = ShouldUseIntraprocess<false>;
|
||||||
|
|
||||||
|
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<typename T>
|
||||||
|
static std::string GetName(int i)
|
||||||
|
{
|
||||||
|
static_cast<void>(i);
|
||||||
|
return T::description;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace
|
||||||
|
|
||||||
|
|
||||||
|
template<typename TestDescription>
|
||||||
|
class TestPublisherSubscriptionCount : public ::testing::Test
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static void SetUpTestCase()
|
static void SetUpTestCase()
|
||||||
|
@ -57,126 +122,128 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void SetUp() {}
|
static void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
|
||||||
|
{
|
||||||
|
(void)msg;
|
||||||
|
}
|
||||||
|
|
||||||
void TearDown() {}
|
std::chrono::milliseconds offset{2000};
|
||||||
|
|
||||||
static std::chrono::milliseconds offset;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
std::chrono::milliseconds TestPublisherSubscriptionCount::offset = std::chrono::milliseconds(2000);
|
/* Testing publisher subscription count api and internal process subscription count.
|
||||||
|
* Two subscriptions in the same topic, both using intraprocess comm.
|
||||||
void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
|
*/
|
||||||
|
struct TwoSubscriptionsIntraprocessComm
|
||||||
{
|
{
|
||||||
(void)msg;
|
static constexpr const char * description =
|
||||||
}
|
"two_subscriptions_intraprocess_comm";
|
||||||
|
using FirstNodeCreationPolicy = NodeCreationPolicy<UseIntraprocess>;
|
||||||
|
using SecondNodeCreationPolicy = NodeCreationPolicy<UseIntraprocess>;
|
||||||
|
|
||||||
TEST_P(TestPublisherSubscriptionCount, increasing_and_decreasing_counts)
|
static constexpr bool first_node_talks_intraprocess{true};
|
||||||
|
static constexpr bool both_nodes_talk_intraprocess{true};
|
||||||
|
};
|
||||||
|
|
||||||
|
/* 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
|
||||||
{
|
{
|
||||||
TestParameters parameters = GetParam();
|
static constexpr const char * description =
|
||||||
|
"two_subscriptions_one_intraprocess_one_not";
|
||||||
|
using FirstNodeCreationPolicy = NodeCreationPolicy<UseIntraprocess>;
|
||||||
|
using SecondNodeCreationPolicy = NodeCreationPolicy<>;
|
||||||
|
|
||||||
|
static constexpr bool first_node_talks_intraprocess{true};
|
||||||
|
static constexpr bool both_nodes_talk_intraprocess{false};
|
||||||
|
};
|
||||||
|
|
||||||
|
/* Testing publisher subscription count api and internal process subscription count.
|
||||||
|
* Two contexts, both using intra-process.
|
||||||
|
*/
|
||||||
|
struct TwoSubscriptionsInTwoContextsWithIntraprocessComm
|
||||||
|
{
|
||||||
|
static constexpr const char * description =
|
||||||
|
"two_subscriptions_in_two_contexts_with_intraprocess_comm";
|
||||||
|
using FirstNodeCreationPolicy = NodeCreationPolicy<UseIntraprocess>;
|
||||||
|
using SecondNodeCreationPolicy = NodeCreationPolicy<UseCustomContext, UseIntraprocess>;
|
||||||
|
|
||||||
|
static constexpr bool first_node_talks_intraprocess{true};
|
||||||
|
static constexpr bool both_nodes_talk_intraprocess{false};
|
||||||
|
};
|
||||||
|
|
||||||
|
/* Testing publisher subscription count api and internal process subscription count.
|
||||||
|
* Two contexts, both of them not using intra-process comm.
|
||||||
|
*/
|
||||||
|
struct TwoSubscriptionsInTwoContextsWithoutIntraprocessComm
|
||||||
|
{
|
||||||
|
static constexpr const char * description =
|
||||||
|
"two_subscriptions_in_two_contexts_without_intraprocess_comm";
|
||||||
|
using FirstNodeCreationPolicy = NodeCreationPolicy<>;
|
||||||
|
using SecondNodeCreationPolicy = NodeCreationPolicy<UseCustomContext>;
|
||||||
|
|
||||||
|
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<rclcpp::Node>(
|
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(
|
||||||
"my_node",
|
"my_node",
|
||||||
"/ns",
|
"/ns",
|
||||||
parameters.node_options[0]);
|
my_node_creation_policy.node_options());
|
||||||
auto publisher = node->create_publisher<Empty>("/topic", 10);
|
auto publisher = node->create_publisher<Empty>("/topic", 10);
|
||||||
|
|
||||||
EXPECT_EQ(publisher->get_subscription_count(), 0u);
|
EXPECT_EQ(publisher->get_subscription_count(), 0u);
|
||||||
EXPECT_EQ(publisher->get_intra_process_subscription_count(), 0u);
|
EXPECT_EQ(publisher->get_intra_process_subscription_count(), 0u);
|
||||||
{
|
{
|
||||||
auto sub = node->create_subscription<Empty>("/topic", 10, &OnMessage);
|
auto sub = node->create_subscription<Empty>(
|
||||||
rclcpp::sleep_for(offset);
|
"/topic", 10, &TestPublisherSubscriptionCount<TestDescription>::OnMessage);
|
||||||
|
rclcpp::sleep_for(this->offset);
|
||||||
EXPECT_EQ(publisher->get_subscription_count(), 1u);
|
EXPECT_EQ(publisher->get_subscription_count(), 1u);
|
||||||
EXPECT_EQ(
|
EXPECT_EQ(
|
||||||
publisher->get_intra_process_subscription_count(),
|
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<rclcpp::Node>(
|
rclcpp::Node::SharedPtr another_node = std::make_shared<rclcpp::Node>(
|
||||||
"another_node",
|
"another_node",
|
||||||
"/ns",
|
"/ns",
|
||||||
parameters.node_options[1]);
|
another_node_creation_policy.node_options());
|
||||||
auto another_sub =
|
auto another_sub = another_node->create_subscription<Empty>(
|
||||||
another_node->create_subscription<Empty>("/topic", 10, &OnMessage);
|
"/topic", 10, &TestPublisherSubscriptionCount<TestDescription>::OnMessage);
|
||||||
|
|
||||||
rclcpp::sleep_for(offset);
|
rclcpp::sleep_for(this->offset);
|
||||||
EXPECT_EQ(publisher->get_subscription_count(), 2u);
|
EXPECT_EQ(publisher->get_subscription_count(), 2u);
|
||||||
EXPECT_EQ(
|
EXPECT_EQ(
|
||||||
publisher->get_intra_process_subscription_count(),
|
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_subscription_count(), 1u);
|
||||||
EXPECT_EQ(
|
EXPECT_EQ(
|
||||||
publisher->get_intra_process_subscription_count(),
|
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.
|
* 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
|
* Subscriptions count checking is always preceeded with an sleep, as random failures had been
|
||||||
* detected without it. */
|
* detected without it. */
|
||||||
rclcpp::sleep_for(offset);
|
rclcpp::sleep_for(this->offset);
|
||||||
EXPECT_EQ(publisher->get_subscription_count(), 0u);
|
EXPECT_EQ(publisher->get_subscription_count(), 0u);
|
||||||
EXPECT_EQ(publisher->get_intra_process_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());
|
|
||||||
|
|
|
@ -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");
|
// Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
// you may not use this file except in compliance with the License.
|
// you may not use this file except in compliance with the License.
|
||||||
|
@ -23,21 +23,79 @@
|
||||||
|
|
||||||
#include "test_msgs/msg/empty.hpp"
|
#include "test_msgs/msg/empty.hpp"
|
||||||
|
|
||||||
using test_msgs::msg::Empty;
|
namespace
|
||||||
|
|
||||||
struct TestParameters
|
|
||||||
{
|
{
|
||||||
rclcpp::NodeOptions node_options;
|
|
||||||
std::string description;
|
template<typename ... Ts>
|
||||||
|
class NodeCreationPolicy
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
rclcpp::NodeOptions & node_options()
|
||||||
|
{
|
||||||
|
return options_;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
rclcpp::NodeOptions options_;
|
||||||
};
|
};
|
||||||
|
|
||||||
std::ostream & operator<<(std::ostream & out, const TestParameters & params)
|
template<typename T, typename ... Ts>
|
||||||
|
class NodeCreationPolicy<T, Ts...>
|
||||||
{
|
{
|
||||||
out << params.description;
|
public:
|
||||||
return out;
|
NodeCreationPolicy()
|
||||||
}
|
{
|
||||||
|
gather<T, Ts...>(options_);
|
||||||
|
}
|
||||||
|
|
||||||
class TestSubscriptionPublisherCount : public ::testing::TestWithParam<TestParameters>
|
rclcpp::NodeOptions & node_options()
|
||||||
|
{
|
||||||
|
return options_;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
template<typename U>
|
||||||
|
static rclcpp::NodeOptions &
|
||||||
|
gather(rclcpp::NodeOptions & options)
|
||||||
|
{
|
||||||
|
return U::gather(options);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename U, typename V, typename ... Ws>
|
||||||
|
static rclcpp::NodeOptions &
|
||||||
|
gather(rclcpp::NodeOptions & options)
|
||||||
|
{
|
||||||
|
return gather<V, Ws...>(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<typename T>
|
||||||
|
static std::string GetName(int i)
|
||||||
|
{
|
||||||
|
static_cast<void>(i);
|
||||||
|
return T::description;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace
|
||||||
|
|
||||||
|
|
||||||
|
template<typename TestDescription>
|
||||||
|
class TestSubscriptionPublisherCount : public ::testing::Test
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
static void SetUpTestCase()
|
static void SetUpTestCase()
|
||||||
|
@ -50,78 +108,59 @@ public:
|
||||||
}
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void SetUp() {}
|
static void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
|
||||||
void TearDown() {}
|
{
|
||||||
static std::chrono::milliseconds offset;
|
(void)msg;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::chrono::milliseconds offset{2000};
|
||||||
};
|
};
|
||||||
|
|
||||||
std::chrono::milliseconds TestSubscriptionPublisherCount::offset = std::chrono::milliseconds(2000);
|
struct OneContextPerTest
|
||||||
|
|
||||||
void OnMessage(const test_msgs::msg::Empty::SharedPtr msg)
|
|
||||||
{
|
{
|
||||||
(void)msg;
|
static constexpr const char * description = "one_context_test";
|
||||||
}
|
using NodeCreationPolicy = ::NodeCreationPolicy<>;
|
||||||
|
};
|
||||||
|
|
||||||
TEST_P(TestSubscriptionPublisherCount, increasing_and_decreasing_counts)
|
struct TwoContextsPerTest
|
||||||
{
|
{
|
||||||
rclcpp::NodeOptions node_options = GetParam().node_options;
|
static constexpr const char * description = "two_contexts_test";
|
||||||
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>(
|
using NodeCreationPolicy = ::NodeCreationPolicy<UseCustomContext>;
|
||||||
"my_node",
|
};
|
||||||
"/ns",
|
|
||||||
node_options);
|
using AllTestDescriptions = ::testing::Types<OneContextPerTest, TwoContextsPerTest>;
|
||||||
auto subscription = node->create_subscription<Empty>("/topic", 10, &OnMessage);
|
TYPED_TEST_CASE(TestSubscriptionPublisherCount, AllTestDescriptions, PrintTestDescription);
|
||||||
|
|
||||||
|
|
||||||
|
using test_msgs::msg::Empty;
|
||||||
|
|
||||||
|
TYPED_TEST(TestSubscriptionPublisherCount, increasing_and_decreasing_counts)
|
||||||
|
{
|
||||||
|
using TestDescription = TypeParam;
|
||||||
|
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("my_node", "/ns");
|
||||||
|
auto subscription = node->create_subscription<Empty>(
|
||||||
|
"/topic", 10, &TestSubscriptionPublisherCount<TestDescription>::OnMessage);
|
||||||
|
|
||||||
EXPECT_EQ(subscription->get_publisher_count(), 0u);
|
EXPECT_EQ(subscription->get_publisher_count(), 0u);
|
||||||
{
|
{
|
||||||
auto pub = node->create_publisher<Empty>("/topic", 10);
|
auto pub = node->create_publisher<Empty>("/topic", 10);
|
||||||
rclcpp::sleep_for(offset);
|
rclcpp::sleep_for(this->offset);
|
||||||
EXPECT_EQ(subscription->get_publisher_count(), 1u);
|
EXPECT_EQ(subscription->get_publisher_count(), 1u);
|
||||||
{
|
{
|
||||||
|
typename TestDescription::NodeCreationPolicy node_creation_policy;
|
||||||
rclcpp::Node::SharedPtr another_node = std::make_shared<rclcpp::Node>(
|
rclcpp::Node::SharedPtr another_node = std::make_shared<rclcpp::Node>(
|
||||||
"another_node",
|
"another_node",
|
||||||
"/ns",
|
"/ns",
|
||||||
node_options);
|
node_creation_policy.node_options());
|
||||||
auto another_pub =
|
auto another_pub =
|
||||||
another_node->create_publisher<Empty>("/topic", 10);
|
another_node->create_publisher<Empty>("/topic", 10);
|
||||||
|
|
||||||
rclcpp::sleep_for(offset);
|
rclcpp::sleep_for(this->offset);
|
||||||
EXPECT_EQ(subscription->get_publisher_count(), 2u);
|
EXPECT_EQ(subscription->get_publisher_count(), 2u);
|
||||||
}
|
}
|
||||||
rclcpp::sleep_for(offset);
|
rclcpp::sleep_for(this->offset);
|
||||||
EXPECT_EQ(subscription->get_publisher_count(), 1u);
|
EXPECT_EQ(subscription->get_publisher_count(), 1u);
|
||||||
}
|
}
|
||||||
rclcpp::sleep_for(offset);
|
rclcpp::sleep_for(this->offset);
|
||||||
EXPECT_EQ(subscription->get_publisher_count(), 0u);
|
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());
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue