Skip to content

Commit

Permalink
Add exhaustive option to spin_some
Browse files Browse the repository at this point in the history
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
  • Loading branch information
ivanpauno committed Jun 5, 2020
1 parent 0f38c51 commit 05625f0
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 3 deletions.
8 changes: 7 additions & 1 deletion rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,10 +169,16 @@ class Executor
* \param[in] max_duration The maximum amount of time to spend executing work, or 0 for no limit.
* Note that spin_some() may take longer than this time as it only returns once max_duration has
* been exceeded.
* \param[in] exhaustive When true, it will try to collect entities again after executing executables
* until there is no more ready entities or the specified duration has been reached.
* When there are subscriptions/clients with long history queues, this will ensure all messages/requestes
* available are handled.
*/
RCLCPP_PUBLIC
virtual void
spin_some(std::chrono::nanoseconds max_duration = std::chrono::nanoseconds(0));
spin_some(
std::chrono::nanoseconds max_duration = std::chrono::nanoseconds(0),
bool exhaustive = false);

RCLCPP_PUBLIC
virtual void
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@ Executor::spin_node_some(std::shared_ptr<rclcpp::Node> node)
}

void
Executor::spin_some(std::chrono::nanoseconds max_duration)
Executor::spin_some(std::chrono::nanoseconds max_duration, bool exhaustive)
{
auto start = std::chrono::steady_clock::now();
auto max_duration_not_elapsed = [max_duration, start]() {
Expand Down Expand Up @@ -242,7 +242,7 @@ Executor::spin_some(std::chrono::nanoseconds max_duration)
execute_any_executable(any_exec);
work_available = true;
} else {
if (!work_available) {
if (!work_available || !exhaustive) {
break;
}
work_available = false;
Expand Down

0 comments on commit 05625f0

Please sign in to comment.