@@ -890,3 +890,119 @@ TYPED_TEST(TestExecutors, testRaceDropCallbackGroupFromSecondThread)
890
890
executor.cancel ();
891
891
executor_thread.join ();
892
892
}
893
+
894
+ TYPED_TEST (TestExecutors, dropSomeTimer)
895
+ {
896
+ using ExecutorType = TypeParam;
897
+ ExecutorType executor;
898
+
899
+ auto node = std::make_shared<rclcpp::Node>(" test_node" );
900
+
901
+ bool timer1_works = false ;
902
+ bool timer2_works = false ;
903
+
904
+ auto timer1 = node->create_timer (std::chrono::milliseconds (10 ), [&timer1_works]() {
905
+ timer1_works = true ;
906
+ });
907
+ auto timer2 = node->create_timer (std::chrono::milliseconds (10 ), [&timer2_works]() {
908
+ timer2_works = true ;
909
+ });
910
+
911
+ executor.add_node (node);
912
+
913
+ // first let's make sure that both timers work
914
+ auto max_end_time = std::chrono::steady_clock::now () + std::chrono::milliseconds (100 );
915
+ while (!timer1_works || !timer2_works) {
916
+ // let the executor pick up the node and the timers
917
+ executor.spin_all (std::chrono::milliseconds (10 ));
918
+
919
+ const auto cur_time = std::chrono::steady_clock::now ();
920
+ ASSERT_LT (cur_time, max_end_time);
921
+ if (cur_time > max_end_time) {
922
+ return ;
923
+ }
924
+ }
925
+
926
+ // delete timer 2. Note, the executor uses an unordered map internally, to order the entities added to the rcl waitset
927
+ // therefore the order is kind of undefined, and this test may be flaky. In case it triggers, something is most likely
928
+ // really broken.
929
+ timer2.reset ();
930
+
931
+ timer1_works = false ;
932
+ timer2_works = false ;
933
+ max_end_time = std::chrono::steady_clock::now () + std::chrono::milliseconds (100 );
934
+ while (!timer1_works && !timer2_works) {
935
+ // let the executor pick up the node and the timers
936
+ executor.spin_all (std::chrono::milliseconds (10 ));
937
+
938
+ const auto cur_time = std::chrono::steady_clock::now ();
939
+ ASSERT_LT (cur_time, max_end_time);
940
+ if (cur_time > max_end_time) {
941
+ return ;
942
+ }
943
+ }
944
+
945
+ ASSERT_TRUE (timer1_works || timer2_works);
946
+ }
947
+
948
+ TYPED_TEST (TestExecutors, dropSomeSubscription)
949
+ {
950
+ using ExecutorType = TypeParam;
951
+ ExecutorType executor;
952
+
953
+ auto node = std::make_shared<rclcpp::Node>(" test_node" );
954
+
955
+ bool sub1_works = false ;
956
+ bool sub2_works = false ;
957
+
958
+ auto sub1 = node->create_subscription <test_msgs::msg::Empty>(" /test_drop" , 10 ,
959
+ [&sub1_works](const test_msgs::msg::Empty & msg) {
960
+ sub1_works = true ;
961
+ });
962
+ auto sub2 = node->create_subscription <test_msgs::msg::Empty>(" /test_drop" , 10 ,
963
+ [&sub2_works](const test_msgs::msg::Empty & msg) {
964
+ sub2_works = true ;
965
+ });
966
+
967
+ auto pub = node->create_publisher <test_msgs::msg::Empty>(" /test_drop" , 10 );
968
+
969
+ executor.add_node (node);
970
+
971
+ // first let's make sure that both timers work
972
+ auto max_end_time = std::chrono::steady_clock::now () + std::chrono::milliseconds (100 );
973
+ while (!sub1_works || !sub2_works) {
974
+ pub->publish (test_msgs::msg::Empty ());
975
+
976
+ // let the executor pick up the node and the timers
977
+ executor.spin_all (std::chrono::milliseconds (10 ));
978
+
979
+ const auto cur_time = std::chrono::steady_clock::now ();
980
+ ASSERT_LT (cur_time, max_end_time);
981
+ if (cur_time > max_end_time) {
982
+ return ;
983
+ }
984
+ }
985
+
986
+ // delete subscription 2. Note, the executor uses an unordered map internally, to order the entities added to the rcl waitset
987
+ // therefore the order is kind of undefined, and this test may be flaky. In case it triggers, something is most likely
988
+ // really broken.
989
+ sub2.reset ();
990
+
991
+ sub1_works = false ;
992
+ sub2_works = false ;
993
+ max_end_time = std::chrono::steady_clock::now () + std::chrono::milliseconds (100 );
994
+ while (!sub1_works && !sub2_works) {
995
+ pub->publish (test_msgs::msg::Empty ());
996
+
997
+ // let the executor pick up the node and the timers
998
+ executor.spin_all (std::chrono::milliseconds (10 ));
999
+
1000
+ const auto cur_time = std::chrono::steady_clock::now ();
1001
+ ASSERT_LT (cur_time, max_end_time);
1002
+ if (cur_time > max_end_time) {
1003
+ return ;
1004
+ }
1005
+ }
1006
+
1007
+ ASSERT_TRUE (sub1_works || sub2_works);
1008
+ }
0 commit comments