Skip to content

Commit 9be01cf

Browse files
Use the same context for the specified node in rclcpp::spin functions… (ros2#2618) (ros2#2620)
Signed-off-by: Tomoya Fujita <[email protected]> Signed-off-by: Kotaro Yoshimoto <[email protected]> (cherry picked from commit 531b2b1) Co-authored-by: Tomoya Fujita <[email protected]>
1 parent e97d4e8 commit 9be01cf

File tree

3 files changed

+38
-3
lines changed

3 files changed

+38
-3
lines changed

rclcpp/include/rclcpp/executors.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -107,7 +107,9 @@ spin_until_future_complete(
107107
const FutureT & future,
108108
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
109109
{
110-
rclcpp::executors::SingleThreadedExecutor executor;
110+
rclcpp::ExecutorOptions options;
111+
options.context = node_ptr->get_context();
112+
rclcpp::executors::SingleThreadedExecutor executor(options);
111113
return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
112114
}
113115

rclcpp/src/rclcpp/executors.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,9 @@
1717
void
1818
rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
1919
{
20-
rclcpp::executors::SingleThreadedExecutor exec;
20+
rclcpp::ExecutorOptions options;
21+
options.context = node_ptr->get_context();
22+
rclcpp::executors::SingleThreadedExecutor exec(options);
2123
exec.spin_node_some(node_ptr);
2224
}
2325

@@ -30,7 +32,9 @@ rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr)
3032
void
3133
rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
3234
{
33-
rclcpp::executors::SingleThreadedExecutor exec;
35+
rclcpp::ExecutorOptions options;
36+
options.context = node_ptr->get_context();
37+
rclcpp::executors::SingleThreadedExecutor exec(options);
3438
exec.add_node(node_ptr);
3539
exec.spin();
3640
exec.remove_node(node_ptr);

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include <algorithm>
2323
#include <chrono>
24+
#include <future>
2425
#include <limits>
2526
#include <memory>
2627
#include <string>
@@ -696,3 +697,31 @@ TYPED_TEST(TestIntraprocessExecutors, testIntraprocessRetrigger) {
696697
executor.spin();
697698
EXPECT_EQ(kNumMessages, this->callback_count.load());
698699
}
700+
701+
// Check spin functions with non default context
702+
TEST(TestExecutors, testSpinWithNonDefaultContext)
703+
{
704+
auto non_default_context = std::make_shared<rclcpp::Context>();
705+
non_default_context->init(0, nullptr);
706+
707+
{
708+
auto node =
709+
std::make_unique<rclcpp::Node>("node", rclcpp::NodeOptions().context(non_default_context));
710+
711+
EXPECT_NO_THROW(rclcpp::spin_some(node->get_node_base_interface()));
712+
713+
auto check_spin_until_future_complete = [&]() {
714+
std::promise<bool> promise;
715+
std::future<bool> future = promise.get_future();
716+
promise.set_value(true);
717+
718+
auto shared_future = future.share();
719+
auto ret = rclcpp::spin_until_future_complete(
720+
node->get_node_base_interface(), shared_future, 1s);
721+
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
722+
};
723+
EXPECT_NO_THROW(check_spin_until_future_complete());
724+
}
725+
726+
rclcpp::shutdown(non_default_context);
727+
}

0 commit comments

Comments
 (0)