Skip to content

Commit 82ce8fb

Browse files
committed
add test to check for execution order of entities in various executors
Signed-off-by: William Woodall <[email protected]>
1 parent 343b29b commit 82ce8fb

File tree

1 file changed

+109
-0
lines changed

1 file changed

+109
-0
lines changed

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 109 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@
3737
#include "rclcpp/guard_condition.hpp"
3838
#include "rclcpp/rclcpp.hpp"
3939
#include "rclcpp/time_source.hpp"
40+
#include "rcpputils/scope_exit.hpp"
4041

4142
#include "test_msgs/msg/empty.hpp"
4243

@@ -878,6 +879,114 @@ TEST(TestExecutors, testSpinWithNonDefaultContext)
878879
rclcpp::shutdown(non_default_context);
879880
}
880881

882+
// The purpose of this test is to check that the order of callbacks happen
883+
// in some relation to the order of events and the order in which the callbacks
884+
// were registered.
885+
// This is not a guarantee of executor API, but it is a bit of UB that some
886+
// have come to depend on, see:
887+
//
888+
// https://github.com/ros2/rclcpp/issues/2532
889+
//
890+
// It should not be changed unless there's a good reason for it (users find it
891+
// the least surprising out come even if it is not guaranteed), but if there
892+
// is a good reason for changing it, then the executors effected can be skipped,
893+
// or the test can be removed.
894+
// The purpose of this test is to catch this regressions and let the authors of
895+
// the change read up on the above context and act accordingly.
896+
TYPED_TEST(TestExecutors, deterministic_execution_order_ub)
897+
{
898+
using ExecutorType = TypeParam;
899+
900+
// number of waitable to test
901+
constexpr size_t number_of_waitables = 10;
902+
std::vector<size_t> forward(number_of_waitables);
903+
std::iota(std::begin(forward), std::end(forward), 0);
904+
std::vector<size_t> reverse(number_of_waitables);
905+
std::reverse_copy(std::begin(forward), std::end(forward), std::begin(reverse));
906+
907+
struct test_case
908+
{
909+
// Order in which to trigger the waitables.
910+
std::vector<size_t> call_order;
911+
// Order in which we expect the waitables to be executed.
912+
std::vector<size_t> expected_execution_order;
913+
};
914+
std::map<std::string, test_case> test_cases = {
915+
{"forward call order", {forward, forward}},
916+
{"reverse call order", {reverse, forward}},
917+
};
918+
919+
// Note use this to exclude or modify expected results for executors if this
920+
// undefined behavior doesn't hold for them:
921+
if (
922+
std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>())
923+
{
924+
// for the EventsExecutor the call order is the execution order because it
925+
// tracks the individual events (triggers in the case of waitables) and
926+
// executes in that order
927+
test_cases["reverse call order"] = {reverse, reverse};
928+
}
929+
930+
// Set up a situation with N waitables, added in order (1, ..., N) and then
931+
// trigger them in various orders between calls to spin, to see that the order
932+
// is impacted by the registration order (in most cases).
933+
// Note that we always add/register, trigger, then wait/spin, because this
934+
// undefined behavior related to execution order only applies to entities
935+
// that were "ready" in between calls to spin, i.e. they appear to become
936+
// "ready" to the executor at the "same time".
937+
// Also note, that this ordering only applies within entities of the same type
938+
// as well, there are other parts of the executor that determine the order
939+
// between entity types, e.g. the default scheduling (at the time of writing)
940+
// prefers timers, then subscriptions, then service servers, then service
941+
// clients, and then waitables, see: Executor::get_next_ready_executable()
942+
// But that might be different for different executors and may change in the
943+
// future.
944+
// So here we just test order withing a few different waitable instances only.
945+
946+
constexpr bool automatically_add_to_executor_with_node = false;
947+
auto isolated_callback_group = this->node->create_callback_group(
948+
rclcpp::CallbackGroupType::MutuallyExclusive,
949+
automatically_add_to_executor_with_node);
950+
951+
auto waitable_interfaces = this->node->get_node_waitables_interface();
952+
953+
std::vector<std::shared_ptr<TestWaitable>> waitables;
954+
for (size_t i = 0; i < number_of_waitables; ++i) {
955+
auto my_waitable = std::make_shared<TestWaitable>();
956+
waitable_interfaces->add_waitable(my_waitable, isolated_callback_group);
957+
waitables.push_back(my_waitable);
958+
}
959+
960+
// perform each of the test cases
961+
for (const auto & test_case_pair : test_cases) {
962+
const std::string & test_case_name = test_case_pair.first;
963+
const auto & test_case = test_case_pair.second;
964+
965+
ExecutorType executor;
966+
executor.add_callback_group(isolated_callback_group, this->node->get_node_base_interface());
967+
968+
RCPPUTILS_SCOPE_EXIT({
969+
for (size_t i = 0; i < number_of_waitables; ++i) {
970+
waitables[i]->set_on_execute_callback(nullptr);
971+
}
972+
});
973+
974+
std::vector<size_t> actual_order;
975+
for (size_t i : test_case.call_order) {
976+
waitables[i]->set_on_execute_callback([&actual_order, i]() {actual_order.push_back(i);});
977+
waitables[i]->trigger();
978+
}
979+
980+
while (actual_order.size() < number_of_waitables) {
981+
executor.spin_once(10s); // large timeout because it should normally exit quickly
982+
}
983+
984+
EXPECT_EQ(actual_order, test_case.expected_execution_order)
985+
<< "callback call order in test case '" << test_case_name << "' different than expected, "
986+
<< "this may be a false positive, see test description";
987+
}
988+
}
989+
881990
template<typename T>
882991
class TestBusyWaiting : public ::testing::Test
883992
{

0 commit comments

Comments
 (0)