@@ -1099,3 +1099,61 @@ TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)
10991099
11001100 ASSERT_TRUE (sub1_works);
11011101}
1102+
1103+ TYPED_TEST (TestExecutors, dropSubscriptionDuringCallback)
1104+ {
1105+ using ExecutorType = TypeParam;
1106+ ExecutorType executor;
1107+
1108+ auto node = std::make_shared<rclcpp::Node>(" test_node" );
1109+
1110+ bool sub1_works = false ;
1111+ bool sub2_works = false ;
1112+
1113+ rclcpp::SubscriptionBase::SharedPtr sub1;
1114+ rclcpp::SubscriptionBase::SharedPtr sub2;
1115+
1116+ // Note, the executor uses an unordered map internally, to order
1117+ // the entities added to the rcl waitset therefore the order of the subscriptions
1118+ // is kind of undefined. Therefore each sub deletes the other one.
1119+ sub1 = node->create_subscription <test_msgs::msg::Empty>(" /test_drop" , 10 ,
1120+ [&sub1_works, &sub2](const test_msgs::msg::Empty &) {
1121+ sub1_works = true ;
1122+ // delete the other subscriber
1123+ sub2.reset ();
1124+ });
1125+ sub2 = node->create_subscription <test_msgs::msg::Empty>(" /test_drop" , 10 ,
1126+ [&sub2_works, &sub1](const test_msgs::msg::Empty &) {
1127+ sub2_works = true ;
1128+ // delete the other subscriber
1129+ sub1.reset ();
1130+ });
1131+
1132+ auto pub = node->create_publisher <test_msgs::msg::Empty>(" /test_drop" , 10 );
1133+
1134+ // wait for both subs to be connected
1135+ auto max_end_time = std::chrono::steady_clock::now () + std::chrono::milliseconds (1500 );
1136+ while ((sub1->get_publisher_count () == 0 ) || (sub2->get_publisher_count () == 0 )) {
1137+ const auto cur_time = std::chrono::steady_clock::now ();
1138+ ASSERT_LT (cur_time, max_end_time);
1139+ }
1140+
1141+ executor.add_node (node);
1142+
1143+ // publish some messages, until one subscriber fired. As both subscribers are
1144+ // connected to the same topic, they should fire in the same wait.
1145+ max_end_time = std::chrono::steady_clock::now () + std::chrono::milliseconds (100 );
1146+ while (!sub1_works && !sub2_works) {
1147+ pub->publish (test_msgs::msg::Empty ());
1148+
1149+ // let the executor pick up the node and the timers
1150+ executor.spin_all (std::chrono::milliseconds (10 ));
1151+
1152+ const auto cur_time = std::chrono::steady_clock::now ();
1153+ ASSERT_LT (cur_time, max_end_time);
1154+ }
1155+
1156+ // only one subscriber must have worked, as the other
1157+ // one was deleted during the callback
1158+ ASSERT_TRUE (!sub1_works || !sub2_works);
1159+ }
0 commit comments