Skip to content

Commit

Permalink
spin_all with a zero timeout.
Browse files Browse the repository at this point in the history
Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya committed Feb 2, 2022
1 parent d3c0049 commit e9b163f
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 9 deletions.
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -305,7 +305,8 @@ class Executor
* If the time that waitables take to be executed is longer than the period on which new waitables
* become ready, this method will execute work repeatedly until `max_duration` has elapsed.
*
* \param[in] max_duration The maximum amount of time to spend executing work. Must be positive.
* \param[in] max_duration The maximum amount of time to spend executing work, must be >= 0.
* \throw throw std::invalid_argument if max_duration is less than 0.
* Note that spin_all() may take longer than this time as it only returns once max_duration has
* been exceeded.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,9 +99,9 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor

/// Static executor implementation of spin all
/**
* This non-blocking function will execute entities until
* timeout or no more work available. If new entities get ready
* while executing work available, they will be executed
* This non-blocking function will execute entities until timeout (must be >= 0)
* or no more work available.
* If new entities get ready while executing work available, they will be executed
* as long as the timeout hasn't expired.
*
* Example:
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 @@ -414,8 +414,8 @@ void Executor::spin_some(std::chrono::nanoseconds max_duration)

void Executor::spin_all(std::chrono::nanoseconds max_duration)
{
if (max_duration <= 0ns) {
throw std::invalid_argument("max_duration must be positive");
if (max_duration < 0ns) {
throw std::invalid_argument("max_duration must be greater than or equal to 0");
}
return this->spin_some_impl(max_duration, true);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,8 @@ StaticSingleThreadedExecutor::spin_some(std::chrono::nanoseconds max_duration)
void
StaticSingleThreadedExecutor::spin_all(std::chrono::nanoseconds max_duration)
{
if (max_duration <= std::chrono::nanoseconds(0)) {
throw std::invalid_argument("max_duration must be positive");
if (max_duration < std::chrono::nanoseconds(0)) {
throw std::invalid_argument("max_duration must be greater than or equal to 0");
}
return this->spin_some_impl(max_duration, true);
}
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -248,7 +248,7 @@ TEST_F(TestExecutor, spin_all_invalid_duration) {

RCLCPP_EXPECT_THROW_EQ(
dummy.spin_all(std::chrono::nanoseconds(-1)),
std::invalid_argument("max_duration must be positive"));
std::invalid_argument("max_duration must be greater than or equal to 0"));
}

TEST_F(TestExecutor, spin_some_in_spin_some) {
Expand Down

0 comments on commit e9b163f

Please sign in to comment.