Skip to content

Commit

Permalink
Add spin_all shortcut
Browse files Browse the repository at this point in the history
Signed-off-by: Tony Najjar <tony.najjar@logivations.com>
  • Loading branch information
Tony Najjar committed Jul 27, 2023
1 parent 22a954e commit 57d52b0
Show file tree
Hide file tree
Showing 4 changed files with 58 additions and 0 deletions.
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

0 comments on commit 57d52b0

Please sign in to comment.