Skip to content

Commit 71f42cc

Browse files
Add stress tests for TimeSource deadlock fix
Tests reproduce the conditions from #2962: - Rapid construct/destroy of nodes with use_sim_time=true (50 cycles) - Concurrent construct/destroy from 4 threads - Toggle use_sim_time while spinning - Verify no lingering thread after destruction If the deadlock is present, these tests will hang and be caught by the 60-second timeout. Signed-off-by: Pavel Guzenfeld <pavelguzenfeld@gmail.com>
1 parent 819de9e commit 71f42cc

2 files changed

Lines changed: 142 additions & 0 deletions

File tree

rclcpp/test/rclcpp/CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -438,6 +438,11 @@ ament_add_ros_isolated_gtest(test_time_source test_time_source.cpp
438438
if(TARGET test_time_source)
439439
target_link_libraries(test_time_source ${PROJECT_NAME} rcl::rcl)
440440
endif()
441+
ament_add_ros_isolated_gtest(test_time_source_deadlock test_time_source_deadlock.cpp
442+
TIMEOUT 60)
443+
if(TARGET test_time_source_deadlock)
444+
target_link_libraries(test_time_source_deadlock ${PROJECT_NAME})
445+
endif()
441446

442447
ament_add_ros_isolated_gtest(test_utilities test_utilities.cpp
443448
APPEND_LIBRARY_DIRS "${append_library_dirs}")
Lines changed: 137 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,137 @@
1+
// Copyright 2026 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
/**
16+
* Stress tests for TimeSource::destroy_clock_sub deadlock fix.
17+
*
18+
* Exercises the conditions from ros2/rclcpp#2962: rapid node
19+
* construction/destruction with use_sim_time enabled. If the
20+
* deadlock is present, these tests will hang (caught by the test
21+
* timeout). Under ThreadSanitizer, any data race or dangling-thread
22+
* access will be flagged.
23+
*/
24+
25+
#include <chrono>
26+
#include <future>
27+
#include <memory>
28+
#include <thread>
29+
#include <vector>
30+
31+
#include "gtest/gtest.h"
32+
33+
#include "rclcpp/rclcpp.hpp"
34+
35+
using namespace std::chrono_literals;
36+
37+
class TestTimeSourceDeadlock : public ::testing::Test
38+
{
39+
public:
40+
static void SetUpTestCase()
41+
{
42+
rclcpp::init(0, nullptr);
43+
}
44+
45+
static void TearDownTestCase()
46+
{
47+
rclcpp::shutdown();
48+
}
49+
};
50+
51+
/// Reproducer for ros2/rclcpp#2962: rapid construction and destruction
52+
/// of a node with use_sim_time=true. The clock executor thread must
53+
/// be joined without deadlock.
54+
TEST_F(TestTimeSourceDeadlock, rapid_construct_destroy_sim_time)
55+
{
56+
for (int i = 0; i < 50; ++i) {
57+
rclcpp::NodeOptions opts;
58+
opts.parameter_overrides({rclcpp::Parameter("use_sim_time", true)});
59+
auto node = std::make_shared<rclcpp::Node>(
60+
"deadlock_test_" + std::to_string(i), "/test_ns", opts);
61+
62+
// Immediately destroy — the clock executor thread must be
63+
// joined without deadlock.
64+
node.reset();
65+
}
66+
}
67+
68+
/// Create and destroy nodes with use_sim_time from multiple threads
69+
/// to stress the lock/join interaction.
70+
TEST_F(TestTimeSourceDeadlock, concurrent_construct_destroy)
71+
{
72+
const int num_threads = 4;
73+
const int iterations = 10;
74+
std::vector<std::future<void>> futures;
75+
76+
for (int t = 0; t < num_threads; ++t) {
77+
futures.push_back(std::async(std::launch::async, [t, iterations]() {
78+
for (int i = 0; i < iterations; ++i) {
79+
rclcpp::NodeOptions opts;
80+
opts.parameter_overrides({rclcpp::Parameter("use_sim_time", true)});
81+
auto node = std::make_shared<rclcpp::Node>(
82+
"concurrent_test_" + std::to_string(t) + "_" + std::to_string(i),
83+
"/test_ns", opts);
84+
node.reset();
85+
}
86+
}));
87+
}
88+
89+
for (auto & f : futures) {
90+
ASSERT_NO_THROW(f.get());
91+
}
92+
}
93+
94+
/// Toggle use_sim_time parameter while spinning — exercises the
95+
/// create_clock_sub / destroy_clock_sub interplay.
96+
TEST_F(TestTimeSourceDeadlock, toggle_use_sim_time_while_spinning)
97+
{
98+
auto node = std::make_shared<rclcpp::Node>("toggle_test", "/test_ns");
99+
rclcpp::executors::SingleThreadedExecutor executor;
100+
executor.add_node(node);
101+
102+
// Spin in background
103+
auto spin_future = std::async(std::launch::async, [&executor]() {
104+
executor.spin();
105+
});
106+
107+
// Toggle use_sim_time several times
108+
for (int i = 0; i < 10; ++i) {
109+
node->set_parameter(rclcpp::Parameter("use_sim_time", true));
110+
std::this_thread::sleep_for(10ms);
111+
node->set_parameter(rclcpp::Parameter("use_sim_time", false));
112+
std::this_thread::sleep_for(10ms);
113+
}
114+
115+
executor.cancel();
116+
spin_future.get();
117+
}
118+
119+
/// Verify the clock thread is properly cleaned up after destruction.
120+
/// After destroying a sim-time node, no threads from its clock
121+
/// executor should be lingering.
122+
TEST_F(TestTimeSourceDeadlock, no_lingering_thread_after_destroy)
123+
{
124+
{
125+
rclcpp::NodeOptions opts;
126+
opts.parameter_overrides({rclcpp::Parameter("use_sim_time", true)});
127+
auto node = std::make_shared<rclcpp::Node>(
128+
"linger_test", "/test_ns", opts);
129+
// Node destroyed here — clock thread must be fully joined
130+
}
131+
132+
// If the thread were dangling, subsequent operations on the
133+
// same context would be unreliable. Create another node to
134+
// verify the context is clean.
135+
auto node2 = std::make_shared<rclcpp::Node>("after_linger", "/test_ns");
136+
ASSERT_NE(node2, nullptr);
137+
}

0 commit comments

Comments
 (0)