Skip to content

Commit af9b7c8

Browse files
committed
Refactor starvation test in multi-threaded executor to use sleep instead of busy wait
Signed-off-by: HarunTeper <[email protected]>
1 parent f6f72c8 commit af9b7c8

File tree

1 file changed

+6
-18
lines changed

1 file changed

+6
-18
lines changed

rclcpp/test/rclcpp/executors/test_multi_threaded_executor.cpp

+6-18
Original file line numberDiff line numberDiff line change
@@ -120,47 +120,35 @@ TEST_F(TestMultiThreadedExecutor, starvation) {
120120
rclcpp::TimerBase::SharedPtr timer_two;
121121

122122
auto timer_one_callback = [&timer_one_count, &timer_two_count]() {
123-
std::cout << "Timer one callback executed. Count: "
124-
<< timer_one_count.load() << std::endl;
125-
126-
auto start_time = std::chrono::steady_clock::now();
127-
while (std::chrono::steady_clock::now() - start_time < 100ms) {
128-
}
123+
std::this_thread::sleep_for(100ms);
129124

130125
timer_one_count++;
131126

132127
auto diff = std::abs(timer_one_count - timer_two_count);
133128

134129
std::cout << "Difference in counts: " << diff << std::endl;
135130

136-
if (diff > 1) {
131+
if (timer_one_count > 10 || timer_two_count > 10) {
137132
rclcpp::shutdown();
138133
ASSERT_LE(diff, 1);
139134
}
140135
};
141136

142137
auto timer_two_callback = [&timer_one_count, &timer_two_count]() {
143-
std::cout << "Timer two callback executed. Count: "
144-
<< timer_two_count.load() << std::endl;
145-
146-
auto start_time = std::chrono::steady_clock::now();
147-
while (std::chrono::steady_clock::now() - start_time < 100ms) {
148-
}
138+
std::this_thread::sleep_for(100ms);
149139

150140
timer_two_count++;
151141

152142
auto diff = std::abs(timer_one_count - timer_two_count);
153143

154-
std::cout << "Difference in counts: " << diff << std::endl;
155-
156-
if (diff > 1) {
144+
if (timer_one_count > 10 || timer_two_count > 10) {
157145
rclcpp::shutdown();
158146
ASSERT_LE(diff, 1);
159147
}
160148
};
161149

162-
timer_one = node->create_wall_timer(0ms, timer_one_callback);
163-
timer_two = node->create_wall_timer(0ms, timer_two_callback);
150+
timer_one = node->create_wall_timer(10ms, timer_one_callback);
151+
timer_two = node->create_wall_timer(10ms, timer_two_callback);
164152

165153
executor.add_node(node);
166154
executor.spin();

0 commit comments

Comments
 (0)