From 707f9cfa8e77ab8b87d82884d024193e653581ea Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Wed, 30 Sep 2020 18:32:56 -0400 Subject: [PATCH] Finish API coverage on executors. (#1364) In particular, add API coverage for spin_node_until_future_complete, spin_until_future_complete, and spin_node_once. Signed-off-by: Chris Lalancette --- .../test/rclcpp/executors/test_executors.cpp | 69 +++++++++++++++++++ rclcpp/test/rclcpp/test_executor.cpp | 34 +++++++++ 2 files changed, 103 insertions(+) diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 9128e17..ac24459 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -335,3 +335,72 @@ TYPED_TEST(TestExecutorsStable, spinSome) { spinner.join(); } + +// Check spin_node_until_future_complete with node base pointer +TYPED_TEST(TestExecutorsStable, testSpinNodeUntilFutureCompleteNodeBasePtr) { + using ExecutorType = TypeParam; + ExecutorType executor; + + std::promise promise; + std::future future = promise.get_future(); + promise.set_value(true); + + auto shared_future = future.share(); + auto ret = rclcpp::executors::spin_node_until_future_complete( + executor, this->node->get_node_base_interface(), shared_future, 1s); + EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); +} + +// Check spin_node_until_future_complete with node pointer +TYPED_TEST(TestExecutorsStable, testSpinNodeUntilFutureCompleteNodePtr) { + using ExecutorType = TypeParam; + ExecutorType executor; + + std::promise promise; + std::future future = promise.get_future(); + promise.set_value(true); + + auto shared_future = future.share(); + auto ret = rclcpp::executors::spin_node_until_future_complete( + executor, this->node, shared_future, 1s); + EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); +} + +// Check spin_until_future_complete with node base pointer (instantiates its own executor) +TEST(TestExecutors, testSpinUntilFutureCompleteNodeBasePtr) { + rclcpp::init(0, nullptr); + + { + auto node = std::make_shared("node"); + + std::promise promise; + std::future future = promise.get_future(); + promise.set_value(true); + + auto shared_future = future.share(); + auto ret = rclcpp::spin_until_future_complete( + node->get_node_base_interface(), shared_future, 1s); + EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); + } + + rclcpp::shutdown(); +} + +// Check spin_until_future_complete with node pointer (instantiates its own executor) +TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr) { + rclcpp::init(0, nullptr); + + { + auto node = std::make_shared("node"); + + std::promise promise; + std::future future = promise.get_future(); + promise.set_value(true); + + auto shared_future = future.share(); + auto ret = rclcpp::spin_until_future_complete(node, shared_future, 1s); + EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); + } + + rclcpp::shutdown(); +} diff --git a/rclcpp/test/rclcpp/test_executor.cpp b/rclcpp/test/rclcpp/test_executor.cpp index 49a836a..d916ec9 100644 --- a/rclcpp/test/rclcpp/test_executor.cpp +++ b/rclcpp/test/rclcpp/test_executor.cpp @@ -321,3 +321,37 @@ TEST_F(TestExecutor, get_group_by_timer_with_deleted_group) { ASSERT_EQ(nullptr, dummy.local_get_group_by_timer(timer).get()); } + +TEST_F(TestExecutor, spin_node_once_base_interface) { + DummyExecutor dummy; + auto node = std::make_shared("node", "ns"); + bool spin_called = false; + auto timer = + node->create_wall_timer( + std::chrono::milliseconds(1), [&]() { + spin_called = true; + }); + + // Wait for the wall timer to have expired. + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + EXPECT_FALSE(spin_called); + dummy.spin_node_once(node->get_node_base_interface()); + EXPECT_TRUE(spin_called); +} + +TEST_F(TestExecutor, spin_node_once_node) { + DummyExecutor dummy; + auto node = std::make_shared("node", "ns"); + bool spin_called = false; + auto timer = + node->create_wall_timer( + std::chrono::milliseconds(1), [&]() { + spin_called = true; + }); + + // Wait for the wall timer to have expired. + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + EXPECT_FALSE(spin_called); + dummy.spin_node_once(node); + EXPECT_TRUE(spin_called); +}