@@ -340,6 +340,53 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, subscriber_triggered_to_receive_mess
340340 EXPECT_TRUE (received_message_future.get ());
341341}
342342
343+ /*
344+ * Test callback group created after spin.
345+ * A subscriber with a new callback group that created after executor spin not received a message
346+ * because the executor can't be triggered while a subscriber created, see
347+ * https://github.com/ros2/rclcpp/issues/2067
348+ */
349+ TYPED_TEST (TestAddCallbackGroupsToExecutor, callback_group_create_after_spin)
350+ {
351+ auto node = std::make_shared<rclcpp::Node>(" my_node" , " /ns" );
352+
353+ // create a publisher to send data
354+ rclcpp::QoS qos = rclcpp::QoS (1 ).reliable ().transient_local ();
355+ rclcpp::Publisher<test_msgs::msg::Empty>::SharedPtr publisher =
356+ node->create_publisher <test_msgs::msg::Empty>(" topic_name" , qos);
357+ publisher->publish (test_msgs::msg::Empty ());
358+
359+ // create a thread running an executor
360+ rclcpp::executors::SingleThreadedExecutor executor;
361+ executor.add_node (node);
362+ std::promise<bool > received_message_promise;
363+ auto received_message_future = received_message_promise.get_future ();
364+ rclcpp::FutureReturnCode return_code = rclcpp::FutureReturnCode::TIMEOUT;
365+ std::thread executor_thread = std::thread (
366+ [&executor, &received_message_future, &return_code]() {
367+ return_code = executor.spin_until_future_complete (received_message_future, 5s);
368+ });
369+
370+ // to create a callback group after spin
371+ std::this_thread::sleep_for (std::chrono::milliseconds (100 ));
372+ rclcpp::CallbackGroup::SharedPtr cb_grp = node->create_callback_group (
373+ rclcpp::CallbackGroupType::MutuallyExclusive);
374+
375+ // expect the subscriber to receive a message
376+ auto sub_callback = [&received_message_promise](test_msgs::msg::Empty::ConstSharedPtr) {
377+ received_message_promise.set_value (true );
378+ };
379+ // create a subscription using the `cb_grp` callback group
380+ auto options = rclcpp::SubscriptionOptions ();
381+ options.callback_group = cb_grp;
382+ rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr subscription =
383+ node->create_subscription <test_msgs::msg::Empty>(" topic_name" , qos, sub_callback, options);
384+
385+ executor_thread.join ();
386+ ASSERT_EQ (rclcpp::FutureReturnCode::SUCCESS, return_code);
387+ EXPECT_TRUE (received_message_future.get ());
388+ }
389+
343390/*
344391 * Test removing callback group from executor that its not associated with.
345392 */
0 commit comments