Skip to content

Commit 3e91d82

Browse files
committed
Added test for starvation in the multi-threaded executor
Signed-off-by: HarunTeper <[email protected]>
1 parent 75643b8 commit 3e91d82

File tree

1 file changed

+63
-0
lines changed

1 file changed

+63
-0
lines changed

rclcpp/test/rclcpp/executors/test_multi_threaded_executor.cpp

Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -102,3 +102,66 @@ TEST_F(TestMultiThreadedExecutor, timer_over_take) {
102102
executor.add_node(node);
103103
executor.spin();
104104
}
105+
106+
/*
107+
Test that no tasks are starved
108+
*/
109+
TEST_F(TestMultiThreadedExecutor, starvation) {
110+
rclcpp::executors::MultiThreadedExecutor executor(rclcpp::ExecutorOptions(),
111+
2u);
112+
113+
std::shared_ptr<rclcpp::Node> node =
114+
std::make_shared<rclcpp::Node>("test_multi_threaded_executor_starvation");
115+
116+
std::atomic_int timer_one_count{0};
117+
std::atomic_int timer_two_count{0};
118+
119+
rclcpp::TimerBase::SharedPtr timer_one;
120+
rclcpp::TimerBase::SharedPtr timer_two;
121+
122+
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+
}
129+
130+
timer_one_count++;
131+
132+
auto diff = std::abs(timer_one_count - timer_two_count);
133+
134+
std::cout << "Difference in counts: " << diff << std::endl;
135+
136+
if (diff > 1) {
137+
rclcpp::shutdown();
138+
ASSERT_LE(diff, 1);
139+
}
140+
};
141+
142+
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+
}
149+
150+
timer_two_count++;
151+
152+
auto diff = std::abs(timer_one_count - timer_two_count);
153+
154+
std::cout << "Difference in counts: " << diff << std::endl;
155+
156+
if (diff > 1) {
157+
rclcpp::shutdown();
158+
ASSERT_LE(diff, 1);
159+
}
160+
};
161+
162+
timer_one = node->create_wall_timer(0ms, timer_one_callback);
163+
timer_two = node->create_wall_timer(0ms, timer_two_callback);
164+
165+
executor.add_node(node);
166+
executor.spin();
167+
}

0 commit comments

Comments
 (0)