Skip to content

Commit 647bd65

Browse files
authored
Make the subscriber_triggered_to_receive_message test more reliable. (#2584)
* Make the subscriber_triggered_to_receive_message test more reliable. In the current code, inside of the timer we create the subscription and the publisher, publish immediately, and expect the subscription to get it immediately. But it may be the case that discovery hasn't even happened between the publisher and the subscription by the time the publish call happens. To make this more reliable, create the subscription and publish *before* we ever create and spin on the timer. This at least gives 100 milliseconds for discovery to happen. That may not be quite enough to make this reliable on all platforms, but in my local testing this helps a lot. Prior to this change I can make this fail one out of 10 times, and after the change I've run 100 times with no failures. Signed-off-by: Chris Lalancette <clalancette@gmail.com>
1 parent 54b8f9c commit 647bd65

File tree

1 file changed

+16
-19
lines changed

1 file changed

+16
-19
lines changed

rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp

Lines changed: 16 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -215,7 +215,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, add_callback_groups_after_add_node_t
215215
std::atomic_size_t timer_count {0};
216216
auto timer_callback = [&executor, &timer_count]() {
217217
auto cur_timer_count = timer_count++;
218-
printf("in timer_callback(%zu)\n", cur_timer_count);
219218
if (cur_timer_count > 0) {
220219
executor.cancel();
221220
}
@@ -344,32 +343,30 @@ TYPED_TEST(TestAddCallbackGroupsToExecutorStable, subscriber_triggered_to_receiv
344343
received_message_promise.set_value(true);
345344
};
346345

347-
rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription;
348-
rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher;
349-
// to create a timer with a callback run on another executor
350-
rclcpp::TimerBase::SharedPtr timer = nullptr;
351346
std::promise<void> timer_promise;
347+
// create a subscription using the 'cb_grp' callback group
348+
rclcpp::QoS qos = rclcpp::QoS(1).reliable();
349+
auto options = rclcpp::SubscriptionOptions();
350+
options.callback_group = cb_grp;
351+
rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription =
352+
node->create_subscription<test_msgs::msg::Empty>("topic_name", qos, sub_callback, options);
353+
// create a publisher to send data
354+
rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher =
355+
node->create_publisher<test_msgs::msg::Empty>("topic_name", qos);
352356
auto timer_callback =
353-
[&subscription, &publisher, &timer, &cb_grp, &node, &sub_callback, &timer_promise]() {
354-
if (timer) {
355-
timer.reset();
357+
[&publisher, &timer_promise]() {
358+
if (publisher->get_subscription_count() == 0) {
359+
// If discovery hasn't happened yet, get out.
360+
return;
356361
}
357-
358-
// create a subscription using the `cb_grp` callback group
359-
rclcpp::QoS qos = rclcpp::QoS(1).reliable();
360-
auto options = rclcpp::SubscriptionOptions();
361-
options.callback_group = cb_grp;
362-
subscription =
363-
node->create_subscription<test_msgs::msg::Empty>("topic_name", qos, sub_callback, options);
364-
// create a publisher to send data
365-
publisher =
366-
node->create_publisher<test_msgs::msg::Empty>("topic_name", qos);
367362
publisher->publish(test_msgs::msg::Empty());
368363
timer_promise.set_value();
369364
};
370365

366+
// Another executor to run the timer with a callback
371367
ExecutorType timer_executor;
372-
timer = node->create_wall_timer(100ms, timer_callback);
368+
369+
rclcpp::TimerBase::SharedPtr timer = node->create_wall_timer(100ms, timer_callback);
373370
timer_executor.add_node(node);
374371
auto future = timer_promise.get_future();
375372
timer_executor.spin_until_future_complete(future);

0 commit comments

Comments
 (0)