@@ -668,26 +668,19 @@ TYPED_TEST(TestExecutorsOnlyNode, missing_event)
668668 rclcpp::Node::SharedPtr node (this ->node );
669669 auto callback_group = node->create_callback_group (
670670 rclcpp::CallbackGroupType::MutuallyExclusive,
671- true );
671+ false );
672672
673673 auto waitable_interfaces = node->get_node_waitables_interface ();
674674 auto my_waitable = std::make_shared<TestWaitable>();
675675 auto my_waitable2 = std::make_shared<TestWaitable>();
676676 waitable_interfaces->add_waitable (my_waitable, callback_group);
677677 waitable_interfaces->add_waitable (my_waitable2, callback_group);
678- executor.add_node ( this -> node );
678+ executor.add_callback_group (callback_group, node-> get_node_base_interface () );
679679
680680 my_waitable->trigger ();
681681 my_waitable2->trigger ();
682682
683- // a node has some default subscribers, that need to get executed first, therefore the loop
684- for (int i = 0 ; i < 10 ; i++) {
685- executor.spin_once (std::chrono::milliseconds (10 ));
686- if (my_waitable->get_count () > 0 ) {
687- // stop execution, after the first waitable has been executed
688- break ;
689- }
690- }
683+ executor.spin_once (std::chrono::milliseconds (10 ));
691684
692685 EXPECT_EQ (1u , my_waitable->get_count ());
693686 EXPECT_EQ (0u , my_waitable2->get_count ());
@@ -696,16 +689,16 @@ TYPED_TEST(TestExecutorsOnlyNode, missing_event)
696689 // This removes my_waitable2 from the list of ready events, and triggers a call to wait_for_work
697690 callback_group->can_be_taken_from ().exchange (false );
698691
699- // now there should be no ready event
692+ // now there should be no ready event
700693 executor.spin_once (std::chrono::milliseconds (10 ));
701694
702695 EXPECT_EQ (1u , my_waitable->get_count ());
703696 EXPECT_EQ (0u , my_waitable2->get_count ());
704697
705- // unblock the callback group
698+ // unblock the callback group
706699 callback_group->can_be_taken_from ().exchange (true );
707700
708- // now the second waitable should get processed
701+ // now the second waitable should get processed
709702 executor.spin_once (std::chrono::milliseconds (10 ));
710703
711704 EXPECT_EQ (1u , my_waitable->get_count ());
0 commit comments