Fixes for unit tests that fail under cyclonedds (#1270)

Addresses #1268 and #1269

Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
brawner 2020-08-11 09:55:32 -07:00
parent 954cc3d27f
commit b17c73992a
2 changed files with 35 additions and 20 deletions

View file

@ -41,28 +41,38 @@ template<typename T>
class TestExecutors : public ::testing::Test class TestExecutors : public ::testing::Test
{ {
public: public:
void SetUp() static void SetUpTestCase()
{ {
rclcpp::init(0, nullptr); rclcpp::init(0, nullptr);
node = std::make_shared<rclcpp::Node>("node", "ns"); }
static void TearDownTestCase()
{
rclcpp::shutdown();
}
void SetUp()
{
const auto test_info = ::testing::UnitTest::GetInstance()->current_test_info();
std::stringstream test_name;
test_name << test_info->test_case_name() << "_" << test_info->name();
node = std::make_shared<rclcpp::Node>("node", test_name.str());
callback_count = 0; callback_count = 0;
std::stringstream topic_name;
const auto test_info = ::testing::UnitTest::GetInstance()->current_test_info();
topic_name << "topic_" << test_info->test_case_name() << "_" << test_info->name();
publisher = node->create_publisher<std_msgs::msg::Empty>(topic_name.str(), rclcpp::QoS(10)); const std::string topic_name = std::string("topic_") + test_name.str();
publisher = node->create_publisher<std_msgs::msg::Empty>(topic_name, rclcpp::QoS(10));
auto callback = [this](std_msgs::msg::Empty::SharedPtr) {this->callback_count++;}; auto callback = [this](std_msgs::msg::Empty::SharedPtr) {this->callback_count++;};
subscription = subscription =
node->create_subscription<std_msgs::msg::Empty>( node->create_subscription<std_msgs::msg::Empty>(
topic_name.str(), rclcpp::QoS(10), std::move(callback)); topic_name, rclcpp::QoS(10), std::move(callback));
} }
void TearDown() void TearDown()
{ {
if (rclcpp::ok()) { publisher.reset();
rclcpp::shutdown(); subscription.reset();
} node.reset();
} }
rclcpp::Node::SharedPtr node; rclcpp::Node::SharedPtr node;
@ -147,7 +157,7 @@ TYPED_TEST(TestExecutorsStable, addTemporaryNode) {
std::thread spinner([&]() {EXPECT_NO_THROW(executor.spin());}); std::thread spinner([&]() {EXPECT_NO_THROW(executor.spin());});
std::this_thread::sleep_for(50ms); std::this_thread::sleep_for(50ms);
rclcpp::shutdown(); executor.cancel();
spinner.join(); spinner.join();
} }
@ -158,6 +168,7 @@ TYPED_TEST(TestExecutors, addNodeTwoExecutors) {
ExecutorType executor2; ExecutorType executor2;
EXPECT_NO_THROW(executor1.add_node(this->node)); EXPECT_NO_THROW(executor1.add_node(this->node));
EXPECT_THROW(executor2.add_node(this->node), std::runtime_error); EXPECT_THROW(executor2.add_node(this->node), std::runtime_error);
executor1.remove_node(this->node, true);
} }
// Check simple spin example // Check simple spin example
@ -172,15 +183,15 @@ TYPED_TEST(TestExecutors, spinWithTimer) {
std::thread spinner([&]() {executor.spin();}); std::thread spinner([&]() {executor.spin();});
auto start = std::chrono::steady_clock::now(); auto start = std::chrono::steady_clock::now();
while (!timer_completed && (std::chrono::steady_clock::now() - start) < 1s) { while (!timer_completed && (std::chrono::steady_clock::now() - start) < 10s) {
std::this_thread::sleep_for(1ms); std::this_thread::sleep_for(1ms);
} }
EXPECT_TRUE(timer_completed); EXPECT_TRUE(timer_completed);
// Cancel needs to be called before join, so that executor.spin() returns.
// Shutdown needs to be called before join, so that executor.spin() returns. executor.cancel();
rclcpp::shutdown();
spinner.join(); spinner.join();
executor.remove_node(this->node, true);
} }
TYPED_TEST(TestExecutors, spinWhileAlreadySpinning) { TYPED_TEST(TestExecutors, spinWhileAlreadySpinning) {
@ -195,7 +206,7 @@ TYPED_TEST(TestExecutors, spinWhileAlreadySpinning) {
// Sleep for a short time to verify executor.spin() is going, and didn't throw. // Sleep for a short time to verify executor.spin() is going, and didn't throw.
auto start = std::chrono::steady_clock::now(); auto start = std::chrono::steady_clock::now();
while (!timer_completed && (std::chrono::steady_clock::now() - start) < 1s) { while (!timer_completed && (std::chrono::steady_clock::now() - start) < 10s) {
std::this_thread::sleep_for(1ms); std::this_thread::sleep_for(1ms);
} }
@ -203,8 +214,9 @@ TYPED_TEST(TestExecutors, spinWhileAlreadySpinning) {
EXPECT_THROW(executor.spin(), std::runtime_error); EXPECT_THROW(executor.spin(), std::runtime_error);
// Shutdown needs to be called before join, so that executor.spin() returns. // Shutdown needs to be called before join, so that executor.spin() returns.
rclcpp::shutdown(); executor.cancel();
spinner.join(); spinner.join();
executor.remove_node(this->node, true);
} }
// Check executor exits immediately if future is complete. // Check executor exits immediately if future is complete.
@ -223,7 +235,7 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureComplete) {
auto start = std::chrono::steady_clock::now(); auto start = std::chrono::steady_clock::now();
auto shared_future = future.share(); auto shared_future = future.share();
auto ret = executor.spin_until_future_complete(shared_future, 1s); auto ret = executor.spin_until_future_complete(shared_future, 1s);
executor.remove_node(this->node, true);
// Check it didn't reach timeout // Check it didn't reach timeout
EXPECT_GT(500ms, (std::chrono::steady_clock::now() - start)); EXPECT_GT(500ms, (std::chrono::steady_clock::now() - start));
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
@ -299,7 +311,7 @@ TYPED_TEST(TestExecutorsStable, spinSome) {
bool spin_exited = false; bool spin_exited = false;
std::thread spinner([&spin_exited, &executor, this]() { std::thread spinner([&spin_exited, &executor, this]() {
executor.spin_some(1s); executor.spin_some(1s);
executor.remove_node(this->node); executor.remove_node(this->node, true);
spin_exited = true; spin_exited = true;
}); });

View file

@ -413,7 +413,10 @@ TEST_F(TestAllocatorMemoryStrategy, add_remove_waitables) {
TEST_F(TestAllocatorMemoryStrategy, number_of_entities_with_subscription) { TEST_F(TestAllocatorMemoryStrategy, number_of_entities_with_subscription) {
RclWaitSetSizes expected_sizes = {}; RclWaitSetSizes expected_sizes = {};
expected_sizes.size_of_subscriptions = 1; expected_sizes.size_of_subscriptions = 1;
if (std::string("rmw_connext_cpp") == rmw_get_implementation_identifier()) { const std::string implementation_identifier = rmw_get_implementation_identifier();
if (implementation_identifier == "rmw_connext_cpp" ||
implementation_identifier == "rmw_cyclonedds_cpp")
{
// For connext, a subscription will also add an event and waitable // For connext, a subscription will also add an event and waitable
expected_sizes.size_of_events += 1; expected_sizes.size_of_events += 1;
expected_sizes.size_of_waitables += 1; expected_sizes.size_of_waitables += 1;