Skip to content

Commit ea4c98c

Browse files
authored
Use the same context for the specified node in rclcpp::spin functions (#2433)
* Use the same conext for the specified node in rclcpp::spin_xx functions Signed-off-by: GitHub <[email protected]> * Add test for spinning with non-default-context Signed-off-by: Kotaro Yoshimoto <[email protected]> * Format code Signed-off-by: Kotaro Yoshimoto <[email protected]> --------- Signed-off-by: GitHub <[email protected]> Signed-off-by: Kotaro Yoshimoto <[email protected]>
1 parent fa59680 commit ea4c98c

File tree

3 files changed

+42
-4
lines changed

3 files changed

+42
-4
lines changed

rclcpp/include/rclcpp/executors.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -120,7 +120,9 @@ spin_until_future_complete(
120120
const FutureT & future,
121121
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
122122
{
123-
rclcpp::executors::SingleThreadedExecutor executor;
123+
rclcpp::ExecutorOptions options;
124+
options.context = node_ptr->get_context();
125+
rclcpp::executors::SingleThreadedExecutor executor(options);
124126
return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
125127
}
126128

rclcpp/src/rclcpp/executors.cpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,9 @@ rclcpp::spin_all(
1919
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
2020
std::chrono::nanoseconds max_duration)
2121
{
22-
rclcpp::executors::SingleThreadedExecutor exec;
22+
rclcpp::ExecutorOptions options;
23+
options.context = node_ptr->get_context();
24+
rclcpp::executors::SingleThreadedExecutor exec(options);
2325
exec.spin_node_all(node_ptr, max_duration);
2426
}
2527

@@ -32,7 +34,9 @@ rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_
3234
void
3335
rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
3436
{
35-
rclcpp::executors::SingleThreadedExecutor exec;
37+
rclcpp::ExecutorOptions options;
38+
options.context = node_ptr->get_context();
39+
rclcpp::executors::SingleThreadedExecutor exec(options);
3640
exec.spin_node_some(node_ptr);
3741
}
3842

@@ -45,7 +49,9 @@ rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr)
4549
void
4650
rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
4751
{
48-
rclcpp::executors::SingleThreadedExecutor exec;
52+
rclcpp::ExecutorOptions options;
53+
options.context = node_ptr->get_context();
54+
rclcpp::executors::SingleThreadedExecutor exec(options);
4955
exec.add_node(node_ptr);
5056
exec.spin();
5157
exec.remove_node(node_ptr);

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -839,3 +839,33 @@ TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr)
839839

840840
rclcpp::shutdown();
841841
}
842+
843+
// Check spin functions with non default context
844+
TEST(TestExecutors, testSpinWithNonDefaultContext)
845+
{
846+
auto non_default_context = std::make_shared<rclcpp::Context>();
847+
non_default_context->init(0, nullptr);
848+
849+
{
850+
auto node =
851+
std::make_unique<rclcpp::Node>("node", rclcpp::NodeOptions().context(non_default_context));
852+
853+
EXPECT_NO_THROW(rclcpp::spin_some(node->get_node_base_interface()));
854+
855+
EXPECT_NO_THROW(rclcpp::spin_all(node->get_node_base_interface(), 1s));
856+
857+
auto check_spin_until_future_complete = [&]() {
858+
std::promise<bool> promise;
859+
std::future<bool> future = promise.get_future();
860+
promise.set_value(true);
861+
862+
auto shared_future = future.share();
863+
auto ret = rclcpp::spin_until_future_complete(
864+
node->get_node_base_interface(), shared_future, 1s);
865+
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
866+
};
867+
EXPECT_NO_THROW(check_spin_until_future_complete());
868+
}
869+
870+
rclcpp::shutdown(non_default_context);
871+
}

0 commit comments

Comments
 (0)