From 14f71f63b32787abab117ba7ce4c7af6724105de Mon Sep 17 00:00:00 2001 From: Rahat Dhande Date: Wed, 21 Jan 2026 05:24:10 -0800 Subject: [PATCH] construct wait set with passed in context (#3021) (cherry picked from commit cd86362f75c730b5ec077befda108019c2bdff35) --- rclcpp/include/rclcpp/wait_for_message.hpp | 2 +- rclcpp/test/rclcpp/test_wait_for_message.cpp | 29 ++++++++++++++++++++ 2 files changed, 30 insertions(+), 1 deletion(-) diff --git a/rclcpp/include/rclcpp/wait_for_message.hpp b/rclcpp/include/rclcpp/wait_for_message.hpp index fab2e6ccfc..58665ec921 100644 --- a/rclcpp/include/rclcpp/wait_for_message.hpp +++ b/rclcpp/include/rclcpp/wait_for_message.hpp @@ -56,7 +56,7 @@ bool wait_for_message( } }); - rclcpp::WaitSet wait_set; + rclcpp::WaitSet wait_set({}, {}, {}, {}, {}, {}, context); wait_set.add_subscription(subscription); RCPPUTILS_SCOPE_EXIT(wait_set.remove_subscription(subscription); ); wait_set.add_guard_condition(gc); diff --git a/rclcpp/test/rclcpp/test_wait_for_message.cpp b/rclcpp/test/rclcpp/test_wait_for_message.cpp index 9f49fb141c..81179ca6fc 100644 --- a/rclcpp/test/rclcpp/test_wait_for_message.cpp +++ b/rclcpp/test/rclcpp/test_wait_for_message.cpp @@ -134,3 +134,32 @@ TEST(TestUtilities, wait_for_last_message) { rclcpp::shutdown(); } + +TEST(TestUtilities, wait_for_message_custom_context) { + auto context = std::make_shared(); + context->init(0, nullptr); + + auto node_opt = rclcpp::NodeOptions().context(context); + auto node = std::make_shared("wait_for_message_custom_context_node", node_opt); + + using MsgT = test_msgs::msg::Strings; + auto pub = node->create_publisher("wait_for_message_topic", 10); + + MsgT out; + auto received = false; + auto wait = std::async( + [&]() { + auto ret = rclcpp::wait_for_message(out, node, "wait_for_message_topic", 5s); + EXPECT_TRUE(ret); + received = true; + }); + + for (auto i = 0u; i < 10 && received == false; ++i) { + pub->publish(*get_messages_strings()[0]); + std::this_thread::sleep_for(1s); + } + ASSERT_TRUE(received); + EXPECT_EQ(out, *get_messages_strings()[0]); + + context->shutdown("test complete"); +}