Skip to content

Commit f6b80ab

Browse files
jmachowinskiJanosch Machowinski
and
Janosch Machowinski
authored
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 <[email protected]> Co-authored-by: Janosch Machowinski <[email protected]>
1 parent 2cc43b3 commit f6b80ab

File tree

1 file changed

+4
-11
lines changed

1 file changed

+4
-11
lines changed

rclcpp/test/rclcpp/executors/test_executors_timer_cancel_behavior.cpp

+4-11
Original file line numberDiff line numberDiff line change
@@ -267,12 +267,15 @@ class TestTimerCancelBehavior : public ::testing::Test
267267

268268
void TearDown()
269269
{
270-
node.reset();
270+
executor.cancel();
271271

272272
// Clean up thread object
273273
if (standalone_thread.joinable()) {
274274
standalone_thread.join();
275275
}
276+
277+
node.reset();
278+
sim_clock_node.reset();
276279
}
277280

278281
std::shared_ptr<TimerNode> node;
@@ -310,7 +313,6 @@ TYPED_TEST(TestTimerCancelBehavior, testTimer1CancelledWithExecutorSpin) {
310313
this->sim_clock_node->sleep_for(50ms);
311314
this->node->CancelTimer1();
312315
this->sim_clock_node->sleep_for(150ms);
313-
this->executor.cancel();
314316

315317
int t1_runs = this->node->GetTimer1Cnt();
316318
int t2_runs = this->node->GetTimer2Cnt();
@@ -328,7 +330,6 @@ TYPED_TEST(TestTimerCancelBehavior, testTimer2CancelledWithExecutorSpin) {
328330
this->sim_clock_node->sleep_for(50ms);
329331
this->node->CancelTimer2();
330332
this->sim_clock_node->sleep_for(150ms);
331-
this->executor.cancel();
332333

333334
int t1_runs = this->node->GetTimer1Cnt();
334335
int t2_runs = this->node->GetTimer2Cnt();
@@ -355,8 +356,6 @@ TYPED_TEST(TestTimerCancelBehavior, testHeadTimerCancelThenResetBehavior) {
355356
int t1_runs_final = this->node->GetTimer1Cnt();
356357
int t2_runs_final = this->node->GetTimer2Cnt();
357358

358-
this->executor.cancel();
359-
360359
// T1 should have been restarted, and execute about 15 additional times.
361360
// Check 10 greater than initial, to account for some timing jitter.
362361
EXPECT_LT(t1_runs_initial + 50, t1_runs_final);
@@ -384,8 +383,6 @@ TYPED_TEST(TestTimerCancelBehavior, testBackTimerCancelThenResetBehavior) {
384383
int t1_runs_final = this->node->GetTimer1Cnt();
385384
int t2_runs_final = this->node->GetTimer2Cnt();
386385

387-
this->executor.cancel();
388-
389386
// T2 should have been restarted, and execute about 15 additional times.
390387
// Check 10 greater than initial, to account for some timing jitter.
391388
EXPECT_LT(t2_runs_initial + 50, t2_runs_final);
@@ -419,8 +416,6 @@ TYPED_TEST(TestTimerCancelBehavior, testBothTimerCancelThenResetT1Behavior) {
419416
int t1_runs_final = this->node->GetTimer1Cnt();
420417
int t2_runs_final = this->node->GetTimer2Cnt();
421418

422-
this->executor.cancel();
423-
424419
// T1 and T2 should have the same initial count.
425420
EXPECT_LE(std::abs(t1_runs_initial - t2_runs_initial), 1);
426421

@@ -458,8 +453,6 @@ TYPED_TEST(TestTimerCancelBehavior, testBothTimerCancelThenResetT2Behavior) {
458453
int t1_runs_final = this->node->GetTimer1Cnt();
459454
int t2_runs_final = this->node->GetTimer2Cnt();
460455

461-
this->executor.cancel();
462-
463456
// T1 and T2 should have the same initial count.
464457
EXPECT_LE(std::abs(t1_runs_initial - t2_runs_initial), 1);
465458

0 commit comments

Comments
 (0)