@@ -904,16 +904,45 @@ TYPED_TEST(TestExecutors, deterministic_execution_order_ub)
904904 std::vector<size_t > reverse (number_of_entities);
905905 std::reverse_copy (std::begin (forward), std::end (forward), std::begin (reverse));
906906
907+ // The expected results vary based on the registration order (always 0..N-1),
908+ // the call order (what this means varies based on the entity type), the
909+ // entity types, and in some cases the executor type.
910+ // It is also possible that the rmw implementation can play a role in the
911+ // ordering, depending on how the executor uses the rmw layer.
912+ // The follow structure and logic tries to capture these details.
913+ // Each test case represents a case-entity pair,
914+ // e.g. "forward call order for waitables" or "reverse call order for timers"
907915 struct test_case
908916 {
909- // Order in which to trigger the waitables.
917+ // If this is true, then the test case should be skipped.
918+ bool should_skip;
919+ // Order in which to invoke the entities, where that is possible to control.
920+ // For example, the order in which we trigger() the waitables, or the
921+ // order in which we set the timers up to execute (using increasing periods).
910922 std::vector<size_t > call_order;
911- // Order in which we expect the waitables to be executed.
923+ // Order in which we expect the entities to be executed by the executor .
912924 std::vector<size_t > expected_execution_order;
913925 };
914- std::map<std::string, test_case> test_cases = {
915- {" forward call order" , {forward, forward}},
916- {" reverse call order" , {reverse, forward}},
926+ // tests cases are "test_name: {"entity type": {call_order, expected_execution_order}"
927+ std::map<std::string, std::map<std::string, test_case>> test_cases = {
928+ {
929+ " forward call order" ,
930+ {
931+ {" waitable" , {false , forward, forward}},
932+ {" subscription" , {false , forward, forward}},
933+ {" timer" , {false , forward, forward}}
934+ }
935+ },
936+ {
937+ " reverse call order" ,
938+ {
939+ {" waitable" , {false , reverse, forward}},
940+ {" subscription" , {false , reverse, forward}},
941+ // timers are always called in order of which expires soonest, so
942+ // the registration order doesn't necessarily affect them
943+ {" timer" , {false , reverse, reverse}}
944+ }
945+ },
917946 };
918947
919948 // Note use this to exclude or modify expected results for executors if this
@@ -924,7 +953,18 @@ TYPED_TEST(TestExecutors, deterministic_execution_order_ub)
924953 // for the EventsExecutor the call order is the execution order because it
925954 // tracks the individual events (triggers in the case of waitables) and
926955 // executes in that order
927- test_cases[" reverse call order" ] = {reverse, reverse};
956+ test_cases[" reverse call order" ][" waitable" ] = {false , reverse, reverse};
957+ // timers are unaffected by the above about waitables, as they are always
958+ // executed in "call order" even in the other executors
959+ // but, subscription execution order is driven by the rmw impl due to
960+ // how the EventsExecutor uses the rmw interface, so we'll skip those
961+ for (auto & test_case_pair : test_cases) {
962+ for (auto & entity_test_case_pair : test_case_pair.second ) {
963+ if (entity_test_case_pair.first == " subscription" ) {
964+ entity_test_case_pair.second = {true , {}, {}};
965+ }
966+ }
967+ }
928968 }
929969
930970 // Set up a situation with N waitables, added in order (1, ..., N) and then
@@ -942,6 +982,8 @@ TYPED_TEST(TestExecutors, deterministic_execution_order_ub)
942982 // But that might be different for different executors and may change in the
943983 // future.
944984 // So here we just test order withing a few different waitable instances only.
985+ // Further down we test similar set ups with other entities like subscriptions
986+ // and timers.
945987
946988 constexpr bool automatically_add_to_executor_with_node = false ;
947989 auto isolated_callback_group = this ->node ->create_callback_group (
@@ -961,7 +1003,10 @@ TYPED_TEST(TestExecutors, deterministic_execution_order_ub)
9611003
9621004 for (const auto & test_case_pair : test_cases) {
9631005 const std::string & test_case_name = test_case_pair.first ;
964- const auto & test_case = test_case_pair.second ;
1006+ const auto & test_case = test_case_pair.second .at (" waitable" );
1007+ if (test_case.should_skip ) {
1008+ continue ;
1009+ }
9651010
9661011 ExecutorType executor;
9671012 executor.add_callback_group (isolated_callback_group, this ->node ->get_node_base_interface ());
@@ -983,54 +1028,49 @@ TYPED_TEST(TestExecutors, deterministic_execution_order_ub)
9831028 }
9841029
9851030 EXPECT_EQ (actual_order, test_case.expected_execution_order )
986- << " callback call order in test case '" << test_case_name << " ' different than expected, "
987- << " this may be a false positive, see test description" ;
1031+ << " callback call order of waitables in test case '" << test_case_name
1032+ << " ' different than expected, this may be a false positive, see test "
1033+ << " description" ;
9881034 }
9891035 }
9901036
991- const std::string test_topic_name = " /deterministic_execution_order_ub" ;
992- std::map<rclcpp::SubscriptionBase *, std::function<void ()>> on_sub_data_callbacks;
993- std::vector<rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr> subscriptions;
994- rclcpp::SubscriptionOptions so;
995- so.callback_group = isolated_callback_group;
996- for (size_t i = 0 ; i < number_of_entities; ++i) {
997- size_t next_sub_index = subscriptions.size ();
998- auto sub = this ->node ->template create_subscription <test_msgs::msg::Empty>(
999- test_topic_name,
1000- 10 ,
1001- [&on_sub_data_callbacks, &subscriptions, next_sub_index](const test_msgs::msg::Empty &) {
1002- auto this_sub_pointer = subscriptions[next_sub_index].get ();
1003- auto callback_for_sub_it = on_sub_data_callbacks.find (this_sub_pointer);
1004- ASSERT_NE (callback_for_sub_it, on_sub_data_callbacks.end ());
1005- auto on_sub_data_callback = callback_for_sub_it->second ;
1006- if (on_sub_data_callback) {
1007- on_sub_data_callback ();
1008- }
1009- },
1010- so);
1011- subscriptions.push_back (sub);
1012- }
1013-
10141037 // perform each of the test cases for subscriptions
1015- if (
1016- // TODO(wjwwood): the order of subscriptions in the EventsExecutor does not
1017- // follow call order or the insertion order, though it seems to be
1018- // consistently the same order (from what I can tell in testing).
1019- // I don't know why that is, but it means that this part of the test
1020- // will not pass for the EventsExecutor, so skip it.
1021- !std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>())
10221038 {
1039+ const std::string test_topic_name = " /deterministic_execution_order_ub" ;
1040+ std::map<rclcpp::SubscriptionBase *, std::function<void ()>> on_sub_data_callbacks;
1041+ std::vector<rclcpp::Subscription<test_msgs::msg::Empty>::SharedPtr> subscriptions;
1042+ rclcpp::SubscriptionOptions so;
1043+ so.callback_group = isolated_callback_group;
1044+ for (size_t i = 0 ; i < number_of_entities; ++i) {
1045+ size_t next_sub_index = subscriptions.size ();
1046+ auto sub = this ->node ->template create_subscription <test_msgs::msg::Empty>(
1047+ test_topic_name,
1048+ 10 ,
1049+ [&on_sub_data_callbacks, &subscriptions, next_sub_index](const test_msgs::msg::Empty &) {
1050+ auto this_sub_pointer = subscriptions[next_sub_index].get ();
1051+ auto callback_for_sub_it = on_sub_data_callbacks.find (this_sub_pointer);
1052+ ASSERT_NE (callback_for_sub_it, on_sub_data_callbacks.end ());
1053+ auto on_sub_data_callback = callback_for_sub_it->second ;
1054+ if (on_sub_data_callback) {
1055+ on_sub_data_callback ();
1056+ }
1057+ },
1058+ so);
1059+ subscriptions.push_back (sub);
1060+ }
1061+
10231062 for (const auto & test_case_pair : test_cases) {
10241063 const std::string & test_case_name = test_case_pair.first ;
1025- const auto & test_case = test_case_pair.second ;
1064+ const auto & test_case = test_case_pair.second .at (" subscription" );
1065+ if (test_case.should_skip ) {
1066+ continue ;
1067+ }
10261068
10271069 ExecutorType executor;
10281070 executor.add_callback_group (isolated_callback_group, this ->node ->get_node_base_interface ());
10291071
10301072 RCPPUTILS_SCOPE_EXIT ({
1031- for (auto & sub_pair : on_sub_data_callbacks) {
1032- sub_pair.second = nullptr ;
1033- }
1073+ on_sub_data_callbacks.clear ();
10341074 });
10351075
10361076 std::vector<size_t > actual_order;
@@ -1056,8 +1096,66 @@ TYPED_TEST(TestExecutors, deterministic_execution_order_ub)
10561096 }
10571097
10581098 EXPECT_EQ (actual_order, test_case.expected_execution_order )
1059- << " callback call order in test case '" << test_case_name << " ' different than expected, "
1060- << " this may be a false positive, see test description" ;
1099+ << " callback call order of subscriptions in test case '" << test_case_name
1100+ << " ' different than expected, this may be a false positive, see test "
1101+ << " description" ;
1102+ }
1103+ }
1104+
1105+ // perform each of the test cases for timers
1106+ {
1107+ for (const auto & test_case_pair : test_cases) {
1108+ const std::string & test_case_name = test_case_pair.first ;
1109+ const auto & test_case = test_case_pair.second .at (" timer" );
1110+ if (test_case.should_skip ) {
1111+ continue ;
1112+ }
1113+
1114+ std::map<rclcpp::TimerBase *, std::function<void ()>> timer_callbacks;
1115+ std::vector<rclcpp::TimerBase::SharedPtr> timers;
1116+ for (size_t i = 0 ; i < number_of_entities; ++i) {
1117+ // "call order" for timers will be simulated by setting them at different
1118+ // periods, with the "first" ones having the smallest period.
1119+ auto period = 1ms + std::chrono::milliseconds (test_case.call_order [i]);
1120+ auto timer = this ->node ->create_timer (
1121+ period,
1122+ [&timer_callbacks](rclcpp::TimerBase & timer) {
1123+ auto timer_callback_it = timer_callbacks.find (&timer);
1124+ ASSERT_NE (timer_callback_it, timer_callbacks.end ());
1125+ if (nullptr != timer_callback_it->second ) {
1126+ timer_callback_it->second ();
1127+ }
1128+ },
1129+ isolated_callback_group);
1130+ timers.push_back (timer);
1131+ }
1132+
1133+ ExecutorType executor;
1134+ executor.add_callback_group (isolated_callback_group, this ->node ->get_node_base_interface ());
1135+
1136+ RCPPUTILS_SCOPE_EXIT ({
1137+ timer_callbacks.clear ();
1138+ });
1139+
1140+ std::vector<size_t > actual_order;
1141+ for (size_t i = 0 ; i < number_of_entities; ++i) {
1142+ ASSERT_LT (i, timers.size ());
1143+ auto & timer = timers[i];
1144+ timer_callbacks[timer.get ()] = [&actual_order, &timer, i]() {
1145+ actual_order.push_back (i);
1146+ // only allow execution once
1147+ timer->cancel ();
1148+ };
1149+ }
1150+
1151+ while (actual_order.size () < number_of_entities && rclcpp::ok ()) {
1152+ executor.spin_once (10s); // large timeout because it should normally exit quickly
1153+ }
1154+
1155+ EXPECT_EQ (actual_order, test_case.expected_execution_order )
1156+ << " callback call order of timers in test case '" << test_case_name
1157+ << " ' different than expected, this may be a false positive, see test "
1158+ << " description" ;
10611159 }
10621160 }
10631161}
0 commit comments