diff --git a/rclcpp/include/rclcpp/executors.hpp b/rclcpp/include/rclcpp/executors.hpp index 55a38709a7..adb9c6d6c6 100644 --- a/rclcpp/include/rclcpp/executors.hpp +++ b/rclcpp/include/rclcpp/executors.hpp @@ -120,7 +120,9 @@ spin_until_future_complete( const FutureT & future, std::chrono::duration timeout = std::chrono::duration(-1)) { - rclcpp::executors::SingleThreadedExecutor executor; + rclcpp::ExecutorOptions options; + options.context = node_ptr->get_context(); + rclcpp::executors::SingleThreadedExecutor executor(options); return executors::spin_node_until_future_complete(executor, node_ptr, future, timeout); } diff --git a/rclcpp/src/rclcpp/executors.cpp b/rclcpp/src/rclcpp/executors.cpp index 3ea8d658ad..94137d50bc 100644 --- a/rclcpp/src/rclcpp/executors.cpp +++ b/rclcpp/src/rclcpp/executors.cpp @@ -19,7 +19,9 @@ rclcpp::spin_all( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, std::chrono::nanoseconds max_duration) { - rclcpp::executors::SingleThreadedExecutor exec; + rclcpp::ExecutorOptions options; + options.context = node_ptr->get_context(); + rclcpp::executors::SingleThreadedExecutor exec(options); exec.spin_node_all(node_ptr, max_duration); } @@ -32,7 +34,9 @@ rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_ void rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) { - rclcpp::executors::SingleThreadedExecutor exec; + rclcpp::ExecutorOptions options; + options.context = node_ptr->get_context(); + rclcpp::executors::SingleThreadedExecutor exec(options); exec.spin_node_some(node_ptr); } @@ -45,7 +49,9 @@ rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr) void rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr) { - rclcpp::executors::SingleThreadedExecutor exec; + rclcpp::ExecutorOptions options; + options.context = node_ptr->get_context(); + rclcpp::executors::SingleThreadedExecutor exec(options); exec.add_node(node_ptr); exec.spin(); exec.remove_node(node_ptr); diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 3434f473c6..1a538eaa30 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -839,3 +839,33 @@ TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr) rclcpp::shutdown(); } + +// Check spin functions with non default context +TEST(TestExecutors, testSpinWithNonDefaultContext) +{ + auto non_default_context = std::make_shared(); + non_default_context->init(0, nullptr); + + { + auto node = + std::make_unique("node", rclcpp::NodeOptions().context(non_default_context)); + + EXPECT_NO_THROW(rclcpp::spin_some(node->get_node_base_interface())); + + EXPECT_NO_THROW(rclcpp::spin_all(node->get_node_base_interface(), 1s)); + + auto check_spin_until_future_complete = [&]() { + 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); + }; + EXPECT_NO_THROW(check_spin_until_future_complete()); + } + + rclcpp::shutdown(non_default_context); +}