From 647bd65e289c1ed4fbf89f1a151fd21040b940c4 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Mon, 22 Jul 2024 14:20:50 -0400 Subject: [PATCH] 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 --- .../test_add_callback_groups_to_executor.cpp | 35 +++++++++---------- 1 file changed, 16 insertions(+), 19 deletions(-) diff --git a/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp b/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp index 70389df1a5..6edcc2cb28 100644 --- a/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp +++ b/rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp @@ -215,7 +215,6 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, add_callback_groups_after_add_node_t std::atomic_size_t timer_count {0}; auto timer_callback = [&executor, &timer_count]() { auto cur_timer_count = timer_count++; - printf("in timer_callback(%zu)\n", cur_timer_count); if (cur_timer_count > 0) { executor.cancel(); } @@ -344,32 +343,30 @@ TYPED_TEST(TestAddCallbackGroupsToExecutorStable, subscriber_triggered_to_receiv received_message_promise.set_value(true); }; - rclcpp::Subscription::SharedPtr subscription; - rclcpp::Publisher::SharedPtr publisher; - // to create a timer with a callback run on another executor - rclcpp::TimerBase::SharedPtr timer = nullptr; std::promise timer_promise; + // create a subscription using the 'cb_grp' callback group + rclcpp::QoS qos = rclcpp::QoS(1).reliable(); + auto options = rclcpp::SubscriptionOptions(); + options.callback_group = cb_grp; + rclcpp::Subscription::SharedPtr subscription = + node->create_subscription("topic_name", qos, sub_callback, options); + // create a publisher to send data + rclcpp::Publisher::SharedPtr publisher = + node->create_publisher("topic_name", qos); auto timer_callback = - [&subscription, &publisher, &timer, &cb_grp, &node, &sub_callback, &timer_promise]() { - if (timer) { - timer.reset(); + [&publisher, &timer_promise]() { + if (publisher->get_subscription_count() == 0) { + // If discovery hasn't happened yet, get out. + return; } - - // create a subscription using the `cb_grp` callback group - rclcpp::QoS qos = rclcpp::QoS(1).reliable(); - auto options = rclcpp::SubscriptionOptions(); - options.callback_group = cb_grp; - subscription = - node->create_subscription("topic_name", qos, sub_callback, options); - // create a publisher to send data - publisher = - node->create_publisher("topic_name", qos); publisher->publish(test_msgs::msg::Empty()); timer_promise.set_value(); }; + // Another executor to run the timer with a callback ExecutorType timer_executor; - timer = node->create_wall_timer(100ms, timer_callback); + + rclcpp::TimerBase::SharedPtr timer = node->create_wall_timer(100ms, timer_callback); timer_executor.add_node(node); auto future = timer_promise.get_future(); timer_executor.spin_until_future_complete(future);