Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add spin_all shortcut #2246

Merged
merged 4 commits into from
Aug 8, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 15 additions & 0 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -297,6 +297,21 @@ class Executor
virtual void
spin_some(std::chrono::nanoseconds max_duration = std::chrono::nanoseconds(0));

/// Add a node, complete all immediately available work exhaustively, and remove the node.
/**
* \param[in] node Shared pointer to the node to add.
*/
RCLCPP_PUBLIC
void
spin_node_all(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
std::chrono::nanoseconds max_duration);

/// Convenience function which takes Node and forwards NodeBaseInterface.
RCLCPP_PUBLIC
void
spin_node_all(std::shared_ptr<rclcpp::Node> node, std::chrono::nanoseconds max_duration);

/// Collect and execute work repeatedly within a duration or until no more work is available.
/**
* This function can be overridden. The default implementation is suitable for a
Expand Down
12 changes: 12 additions & 0 deletions rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,18 @@
namespace rclcpp
{

/// Create a default single-threaded executor and execute all available work exhaustively.
/** \param[in] node_ptr Shared pointer to the node to spin. */
RCLCPP_PUBLIC
void
spin_all(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
std::chrono::nanoseconds max_duration);

RCLCPP_PUBLIC
void
spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration);

/// Create a default single-threaded executor and execute any immediately available work.
/** \param[in] node_ptr Shared pointer to the node to spin. */
RCLCPP_PUBLIC
Expand Down
16 changes: 16 additions & 0 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -431,6 +431,22 @@ void Executor::spin_some(std::chrono::nanoseconds max_duration)
return this->spin_some_impl(max_duration, false);
}

void
Executor::spin_node_all(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
std::chrono::nanoseconds max_duration)
{
this->add_node(node, false);
spin_all(max_duration);
this->remove_node(node, false);
}

void
Executor::spin_node_all(std::shared_ptr<rclcpp::Node> node, std::chrono::nanoseconds max_duration)
{
this->spin_node_all(node->get_node_base_interface(), max_duration);
}

void Executor::spin_all(std::chrono::nanoseconds max_duration)
{
if (max_duration < 0ns) {
Expand Down
15 changes: 15 additions & 0 deletions rclcpp/src/rclcpp/executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,21 @@

#include "rclcpp/executors.hpp"

void
rclcpp::spin_all(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
std::chrono::nanoseconds max_duration)
{
rclcpp::executors::SingleThreadedExecutor exec;
exec.spin_node_all(node_ptr, max_duration);
}

void
rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration)
{
rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration);
}

void
rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
{
Expand Down
34 changes: 34 additions & 0 deletions rclcpp/test/rclcpp/test_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -546,6 +546,40 @@ TEST_F(TestExecutor, spin_node_once_node) {
EXPECT_TRUE(spin_called);
}

TEST_F(TestExecutor, spin_node_all_base_interface) {
DummyExecutor dummy;
auto node = std::make_shared<rclcpp::Node>("node", "ns");
bool spin_called = false;
auto timer =
node->create_wall_timer(
std::chrono::milliseconds(1), [&]() {
spin_called = true;
});

// Wait for the wall timer to have expired.
std::this_thread::sleep_for(std::chrono::milliseconds(50));
EXPECT_FALSE(spin_called);
dummy.spin_node_all(node->get_node_base_interface(), std::chrono::milliseconds(50));
EXPECT_TRUE(spin_called);
}

TEST_F(TestExecutor, spin_node_all_node) {
DummyExecutor dummy;
auto node = std::make_shared<rclcpp::Node>("node", "ns");
bool spin_called = false;
auto timer =
node->create_wall_timer(
std::chrono::milliseconds(1), [&]() {
spin_called = true;
});

// Wait for the wall timer to have expired.
std::this_thread::sleep_for(std::chrono::milliseconds(50));
EXPECT_FALSE(spin_called);
dummy.spin_node_all(node, std::chrono::milliseconds(50));
EXPECT_TRUE(spin_called);
}

TEST_F(TestExecutor, spin_until_future_complete_future_already_complete) {
DummyExecutor dummy;
auto node = std::make_shared<rclcpp::Node>("node", "ns");
Expand Down