From f6b80abe4aec0f6284fb42f3b122e5f8574d2649 Mon Sep 17 00:00:00 2001 From: Janosch Machowinski Date: Mon, 10 Feb 2025 19:45:30 +0100 Subject: [PATCH] fix(timer): Delete node, after executor thread terminated (#2737) This fixes a potential race leading to a segfault. The segfault would happen, if the tear down of the test would occur before the timer thread stopped the spinning of the executor. Also simplifies the test code, as the cancel of the executor is now in the TearDown(). Signed-off-by: Janosch Machowinski Co-authored-by: Janosch Machowinski --- .../test_executors_timer_cancel_behavior.cpp | 15 ++++----------- 1 file changed, 4 insertions(+), 11 deletions(-) diff --git a/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp b/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp index fbf38146fb..ea1007a779 100644 --- a/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp @@ -267,12 +267,15 @@ class TestTimerCancelBehavior : public ::testing::Test void TearDown() { - node.reset(); + executor.cancel(); // Clean up thread object if (standalone_thread.joinable()) { standalone_thread.join(); } + + node.reset(); + sim_clock_node.reset(); } std::shared_ptr node; @@ -310,7 +313,6 @@ TYPED_TEST(TestTimerCancelBehavior, testTimer1CancelledWithExecutorSpin) { this->sim_clock_node->sleep_for(50ms); this->node->CancelTimer1(); this->sim_clock_node->sleep_for(150ms); - this->executor.cancel(); int t1_runs = this->node->GetTimer1Cnt(); int t2_runs = this->node->GetTimer2Cnt(); @@ -328,7 +330,6 @@ TYPED_TEST(TestTimerCancelBehavior, testTimer2CancelledWithExecutorSpin) { this->sim_clock_node->sleep_for(50ms); this->node->CancelTimer2(); this->sim_clock_node->sleep_for(150ms); - this->executor.cancel(); int t1_runs = this->node->GetTimer1Cnt(); int t2_runs = this->node->GetTimer2Cnt(); @@ -355,8 +356,6 @@ TYPED_TEST(TestTimerCancelBehavior, testHeadTimerCancelThenResetBehavior) { int t1_runs_final = this->node->GetTimer1Cnt(); int t2_runs_final = this->node->GetTimer2Cnt(); - this->executor.cancel(); - // T1 should have been restarted, and execute about 15 additional times. // Check 10 greater than initial, to account for some timing jitter. EXPECT_LT(t1_runs_initial + 50, t1_runs_final); @@ -384,8 +383,6 @@ TYPED_TEST(TestTimerCancelBehavior, testBackTimerCancelThenResetBehavior) { int t1_runs_final = this->node->GetTimer1Cnt(); int t2_runs_final = this->node->GetTimer2Cnt(); - this->executor.cancel(); - // T2 should have been restarted, and execute about 15 additional times. // Check 10 greater than initial, to account for some timing jitter. EXPECT_LT(t2_runs_initial + 50, t2_runs_final); @@ -419,8 +416,6 @@ TYPED_TEST(TestTimerCancelBehavior, testBothTimerCancelThenResetT1Behavior) { int t1_runs_final = this->node->GetTimer1Cnt(); int t2_runs_final = this->node->GetTimer2Cnt(); - this->executor.cancel(); - // T1 and T2 should have the same initial count. EXPECT_LE(std::abs(t1_runs_initial - t2_runs_initial), 1); @@ -458,8 +453,6 @@ TYPED_TEST(TestTimerCancelBehavior, testBothTimerCancelThenResetT2Behavior) { int t1_runs_final = this->node->GetTimer1Cnt(); int t2_runs_final = this->node->GetTimer2Cnt(); - this->executor.cancel(); - // T1 and T2 should have the same initial count. EXPECT_LE(std::abs(t1_runs_initial - t2_runs_initial), 1);