Skip to content

Commit

Permalink
Use the same context for the specified node in rclcpp::spin functions (
Browse files Browse the repository at this point in the history
…#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]>
  • Loading branch information
HansRobo authored Apr 6, 2024
1 parent fa59680 commit ea4c98c
Show file tree
Hide file tree
Showing 3 changed files with 42 additions and 4 deletions.
4 changes: 3 additions & 1 deletion rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,9 @@ spin_until_future_complete(
const FutureT & future,
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-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<FutureT>(executor, node_ptr, future, timeout);
}

Expand Down
12 changes: 9 additions & 3 deletions rclcpp/src/rclcpp/executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand All @@ -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);
}

Expand All @@ -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);
Expand Down
30 changes: 30 additions & 0 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::Context>();
non_default_context->init(0, nullptr);

{
auto node =
std::make_unique<rclcpp::Node>("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<bool> promise;
std::future<bool> 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);
}

0 comments on commit ea4c98c

Please sign in to comment.