2020#include < gtest/gtest.h>
2121
2222#include < algorithm>
23+ #include < atomic>
2324#include < chrono>
2425#include < limits>
2526#include < memory>
2627#include < string>
2728#include < thread>
2829#include < utility>
30+ #include < vector>
2931
3032#include " rcl/error_handling.h"
3133#include " rcl/time.h"
@@ -43,18 +45,10 @@ template<typename T>
4345class TestExecutors : public ::testing::Test
4446{
4547public:
46- static void SetUpTestCase ()
48+ void SetUp ()
4749 {
4850 rclcpp::init (0 , nullptr );
49- }
50-
51- static void TearDownTestCase ()
52- {
53- rclcpp::shutdown ();
54- }
5551
56- void SetUp ()
57- {
5852 const auto test_info = ::testing::UnitTest::GetInstance ()->current_test_info ();
5953 std::stringstream test_name;
6054 test_name << test_info->test_case_name () << " _" << test_info->name ();
@@ -75,6 +69,8 @@ class TestExecutors : public ::testing::Test
7569 publisher.reset ();
7670 subscription.reset ();
7771 node.reset ();
72+
73+ rclcpp::shutdown ();
7874 }
7975
8076 rclcpp::Node::SharedPtr node;
@@ -729,6 +725,77 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteInterrupted)
729725 spinner.join ();
730726}
731727
728+ // This test verifies that the add_node operation is robust wrt race conditions.
729+ // It's mostly meant to prevent regressions in the events-executor, but the operation should be
730+ // thread-safe in all executor implementations.
731+ // The initial implementation of the events-executor contained a bug where the executor
732+ // would end up in an inconsistent state and stop processing interrupt/shutdown notifications.
733+ // Manually adding a node to the executor results in a) producing a notify waitable event
734+ // and b) refreshing the executor collections.
735+ // The inconsistent state would happen if the event was processed before the collections were
736+ // finished to be refreshed: the executor would pick up the event but be unable to process it.
737+ // This would leave the `notify_waitable_event_pushed_` flag to true, preventing additional
738+ // notify waitable events to be pushed.
739+ // The behavior is observable only under heavy load, so this test spawns several worker
740+ // threads. Due to the nature of the bug, this test may still succeed even if the
741+ // bug is present. However repeated runs will show its flakiness nature and indicate
742+ // an eventual regression.
743+ TYPED_TEST (TestExecutors, testRaceConditionAddNode)
744+ {
745+ using ExecutorType = TypeParam;
746+ // rmw_connextdds doesn't support events-executor
747+ if (
748+ std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
749+ std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
750+ {
751+ GTEST_SKIP ();
752+ }
753+
754+ // Spawn some threads to do some heavy work
755+ std::atomic<bool > should_cancel = false ;
756+ std::vector<std::thread> stress_threads;
757+ for (size_t i = 0 ; i < 5 * std::thread::hardware_concurrency (); i++) {
758+ stress_threads.emplace_back (
759+ [&should_cancel, i]() {
760+ // This is just some arbitrary heavy work
761+ volatile size_t total = 0 ;
762+ for (size_t k = 0 ; k < 549528914167 ; k++) {
763+ if (should_cancel) {
764+ break ;
765+ }
766+ total += k * (i + 42 );
767+ }
768+ });
769+ }
770+
771+ // Create an executor
772+ auto executor = std::make_shared<ExecutorType>();
773+ // Start spinning
774+ auto executor_thread = std::thread (
775+ [executor]() {
776+ executor->spin ();
777+ });
778+ // Add a node to the executor
779+ executor->add_node (this ->node );
780+
781+ // Cancel the executor (make sure that it's already spinning first)
782+ while (!executor->is_spinning () && rclcpp::ok ()) {
783+ continue ;
784+ }
785+ executor->cancel ();
786+
787+ // Try to join the thread after cancelling the executor
788+ // This is the "test". We want to make sure that we can still cancel the executor
789+ // regardless of the presence of race conditions
790+ executor_thread.join ();
791+
792+ // The test is now completed: we can join the stress threads
793+ should_cancel = true ;
794+ for (auto & t : stress_threads) {
795+ t.join ();
796+ }
797+ }
798+
732799// Check spin_until_future_complete with node base pointer (instantiates its own executor)
733800TEST (TestExecutors, testSpinUntilFutureCompleteNodeBasePtr)
734801{
0 commit comments