Skip to content

Commit

Permalink
Merge pull request #1871 from ros2/asoragna/executor-is-spinning
Browse files Browse the repository at this point in the history
add is_spinning() method to executor base class
  • Loading branch information
alsora authored Jan 21, 2022
2 parents c54a6f1 + 9ec0393 commit d3c0049
Show file tree
Hide file tree
Showing 3 changed files with 36 additions and 0 deletions.
9 changes: 9 additions & 0 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -401,6 +401,15 @@ class Executor
void
set_memory_strategy(memory_strategy::MemoryStrategy::SharedPtr memory_strategy);

/// Returns true if the executor is currently spinning.
/**
* This function can be called asynchronously from any thread.
* \return True if the executor is currently spinning.
*/
RCLCPP_PUBLIC
bool
is_spinning();

protected:
RCLCPP_PUBLIC
void
Expand Down
6 changes: 6 additions & 0 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -928,3 +928,9 @@ Executor::has_node(
return other_ptr == node_ptr;
}) != weak_groups_to_nodes.end();
}

bool
Executor::is_spinning()
{
return spinning;
}
21 changes: 21 additions & 0 deletions rclcpp/test/rclcpp/test_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -556,3 +556,24 @@ TEST_F(TestExecutor, spin_until_future_complete_future_already_complete) {
rclcpp::FutureReturnCode::SUCCESS,
dummy.spin_until_future_complete(future, std::chrono::milliseconds(1)));
}

TEST_F(TestExecutor, is_spinning) {
DummyExecutor dummy;
ASSERT_FALSE(dummy.is_spinning());

auto node = std::make_shared<rclcpp::Node>("node", "ns");
bool timer_called = false;
auto timer =
node->create_wall_timer(
std::chrono::milliseconds(1), [&]() {
timer_called = true;
EXPECT_TRUE(dummy.is_spinning());
});

dummy.add_node(node);
// Wait for the wall timer to have expired.
std::this_thread::sleep_for(std::chrono::milliseconds(50));
dummy.spin_some(std::chrono::milliseconds(1));

ASSERT_TRUE(timer_called);
}

0 comments on commit d3c0049

Please sign in to comment.