Skip to content

Commit d3c0049

Browse files
authored
Merge pull request #1871 from ros2/asoragna/executor-is-spinning
add is_spinning() method to executor base class
2 parents c54a6f1 + 9ec0393 commit d3c0049

File tree

3 files changed

+36
-0
lines changed

3 files changed

+36
-0
lines changed

rclcpp/include/rclcpp/executor.hpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -401,6 +401,15 @@ class Executor
401401
void
402402
set_memory_strategy(memory_strategy::MemoryStrategy::SharedPtr memory_strategy);
403403

404+
/// Returns true if the executor is currently spinning.
405+
/**
406+
* This function can be called asynchronously from any thread.
407+
* \return True if the executor is currently spinning.
408+
*/
409+
RCLCPP_PUBLIC
410+
bool
411+
is_spinning();
412+
404413
protected:
405414
RCLCPP_PUBLIC
406415
void

rclcpp/src/rclcpp/executor.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -928,3 +928,9 @@ Executor::has_node(
928928
return other_ptr == node_ptr;
929929
}) != weak_groups_to_nodes.end();
930930
}
931+
932+
bool
933+
Executor::is_spinning()
934+
{
935+
return spinning;
936+
}

rclcpp/test/rclcpp/test_executor.cpp

Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -556,3 +556,24 @@ TEST_F(TestExecutor, spin_until_future_complete_future_already_complete) {
556556
rclcpp::FutureReturnCode::SUCCESS,
557557
dummy.spin_until_future_complete(future, std::chrono::milliseconds(1)));
558558
}
559+
560+
TEST_F(TestExecutor, is_spinning) {
561+
DummyExecutor dummy;
562+
ASSERT_FALSE(dummy.is_spinning());
563+
564+
auto node = std::make_shared<rclcpp::Node>("node", "ns");
565+
bool timer_called = false;
566+
auto timer =
567+
node->create_wall_timer(
568+
std::chrono::milliseconds(1), [&]() {
569+
timer_called = true;
570+
EXPECT_TRUE(dummy.is_spinning());
571+
});
572+
573+
dummy.add_node(node);
574+
// Wait for the wall timer to have expired.
575+
std::this_thread::sleep_for(std::chrono::milliseconds(50));
576+
dummy.spin_some(std::chrono::milliseconds(1));
577+
578+
ASSERT_TRUE(timer_called);
579+
}

0 commit comments

Comments
 (0)