Skip to content

Commit 891fff0

Browse files
author
Chen Lihui
authored
fix one subscription can wait_for_message twice (#1870)
Signed-off-by: Chen Lihui <[email protected]>
1 parent 43db06d commit 891fff0

File tree

2 files changed

+38
-0
lines changed

2 files changed

+38
-0
lines changed

rclcpp/include/rclcpp/wait_for_message.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,8 @@
1818
#include <memory>
1919
#include <string>
2020

21+
#include "rcpputils/scope_exit.hpp"
22+
2123
#include "rclcpp/node.hpp"
2224
#include "rclcpp/visibility_control.hpp"
2325
#include "rclcpp/wait_set.hpp"
@@ -54,6 +56,7 @@ bool wait_for_message(
5456

5557
rclcpp::WaitSet wait_set;
5658
wait_set.add_subscription(subscription);
59+
RCPPUTILS_SCOPE_EXIT(wait_set.remove_subscription(subscription); );
5760
wait_set.add_guard_condition(gc);
5861
auto ret = wait_set.wait(time_to_wait);
5962
if (ret.kind() != rclcpp::WaitResultKind::Ready) {

rclcpp/test/rclcpp/test_wait_for_message.cpp

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -72,3 +72,38 @@ TEST(TestUtilities, wait_for_message_indefinitely) {
7272

7373
ASSERT_FALSE(received);
7474
}
75+
76+
TEST(TestUtilities, wait_for_message_twice_one_sub) {
77+
rclcpp::init(0, nullptr);
78+
79+
auto node = std::make_shared<rclcpp::Node>("wait_for_message_node3");
80+
81+
using MsgT = test_msgs::msg::Strings;
82+
auto pub = node->create_publisher<MsgT>("wait_for_message_topic", 10);
83+
auto sub = node->create_subscription<MsgT>(
84+
"wait_for_message_topic", 1, [](const std::shared_ptr<const MsgT>) {});
85+
86+
MsgT out1;
87+
MsgT out2;
88+
auto received = false;
89+
auto wait = std::async(
90+
[&]() {
91+
auto ret = rclcpp::wait_for_message(out1, sub, node->get_node_options().context(), 5s);
92+
EXPECT_TRUE(ret);
93+
ret = rclcpp::wait_for_message(out2, sub, node->get_node_options().context(), 5s);
94+
EXPECT_TRUE(ret);
95+
received = true;
96+
});
97+
98+
for (auto i = 0u; i < 10 && received == false; ++i) {
99+
pub->publish(*get_messages_strings()[0]);
100+
std::this_thread::sleep_for(1s);
101+
}
102+
103+
ASSERT_NO_THROW(wait.get());
104+
ASSERT_TRUE(received);
105+
EXPECT_EQ(out1, *get_messages_strings()[0]);
106+
EXPECT_EQ(out2, *get_messages_strings()[0]);
107+
108+
rclcpp::shutdown();
109+
}

0 commit comments

Comments
 (0)