@@ -796,60 +796,6 @@ TYPED_TEST(TestExecutors, testRaceConditionAddNode)
796796 }
797797}
798798
799- // This test verifies the thread-safety of adding and removing a node
800- // while the executor is spinning and events are ready.
801- // This test does not contain expectations, but rather it verifies that
802- // we can run a "stressful routine" without crashing.
803- TYPED_TEST (TestExecutors, stressAddRemoveNode)
804- {
805- using ExecutorType = TypeParam;
806- // rmw_connextdds doesn't support events-executor
807- if (
808- std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>() &&
809- std::string (rmw_get_implementation_identifier ()).find (" rmw_connextdds" ) == 0 )
810- {
811- GTEST_SKIP ();
812- }
813-
814- ExecutorType executor;
815-
816- // A timer that is "always" ready (the timer callback doesn't do anything)
817- auto timer = this ->node ->create_wall_timer (std::chrono::nanoseconds (1 ), []() {});
818-
819- // This thread spins the executor until it's cancelled
820- std::thread spinner_thread ([&]() {
821- executor.spin ();
822- });
823-
824- // This thread publishes data in a busy loop (the node has a subscription)
825- std::thread publisher_thread1 ([&]() {
826- for (size_t i = 0 ; i < 100000 ; i++) {
827- this ->publisher ->publish (test_msgs::msg::Empty ());
828- }
829- });
830- std::thread publisher_thread2 ([&]() {
831- for (size_t i = 0 ; i < 100000 ; i++) {
832- this ->publisher ->publish (test_msgs::msg::Empty ());
833- }
834- });
835-
836- // This thread adds/remove the node that contains the entities in a busy loop
837- std::thread add_remove_thread ([&]() {
838- for (size_t i = 0 ; i < 100000 ; i++) {
839- executor.add_node (this ->node );
840- executor.remove_node (this ->node );
841- }
842- });
843-
844- // Wait for the threads that do real work to finish
845- publisher_thread1.join ();
846- publisher_thread2.join ();
847- add_remove_thread.join ();
848-
849- executor.cancel ();
850- spinner_thread.join ();
851- }
852-
853799// Check spin_until_future_complete with node base pointer (instantiates its own executor)
854800TEST (TestExecutors, testSpinUntilFutureCompleteNodeBasePtr)
855801{
0 commit comments