Skip to content

Commit 36d56c5

Browse files
christophebedard-apexaihliberackifujitatomoya
committed
Add spin_until_complete and spin_for
Co-authored-by: Hubert Liberacki <[email protected]> Co-authored-by: Tomoya Fujita <[email protected]> Signed-off-by: Hubert Liberacki <[email protected]> Signed-off-by: Tomoya Fujita <[email protected]> Signed-off-by: Christophe Bedard <[email protected]>
1 parent f9c4894 commit 36d56c5

File tree

5 files changed

+194
-24
lines changed

5 files changed

+194
-24
lines changed

rclcpp/include/rclcpp/executor.hpp

Lines changed: 47 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -350,32 +350,22 @@ class Executor
350350
virtual void
351351
spin_once(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
352352

353-
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
353+
/// Spin (blocking) until the condition is complete, it times out waiting, or rclcpp is
354+
/// interrupted.
354355
/**
355-
* \param[in] future The future to wait on. If this function returns SUCCESS, the future can be
356-
* accessed without blocking (though it may still throw an exception).
356+
* \param[in] condition The callable condition to wait on.
357357
* \param[in] timeout Optional timeout parameter, which gets passed to Executor::spin_node_once.
358358
* `-1` is block forever, `0` is non-blocking.
359359
* If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return
360360
* code.
361361
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
362362
*/
363-
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
363+
template<typename TimeRepT = int64_t, typename TimeT = std::milli>
364364
FutureReturnCode
365-
spin_until_future_complete(
366-
const FutureT & future,
365+
spin_until_complete(
366+
const std::function<bool(void)> & condition,
367367
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
368368
{
369-
// TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
370-
// inside a callback executed by an executor.
371-
372-
// Check the future before entering the while loop.
373-
// If the future is already complete, don't try to spin.
374-
std::future_status status = future.wait_for(std::chrono::seconds(0));
375-
if (status == std::future_status::ready) {
376-
return FutureReturnCode::SUCCESS;
377-
}
378-
379369
auto end_time = std::chrono::steady_clock::now();
380370
std::chrono::nanoseconds timeout_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
381371
timeout);
@@ -384,17 +374,20 @@ class Executor
384374
}
385375
std::chrono::nanoseconds timeout_left = timeout_ns;
386376

377+
// Preliminary check, finish if condition is done already.
378+
if (condition()) {
379+
return FutureReturnCode::SUCCESS;
380+
}
381+
387382
if (spinning.exchange(true)) {
388-
throw std::runtime_error("spin_until_future_complete() called while already spinning");
383+
throw std::runtime_error("spin_until_complete() called while already spinning");
389384
}
390385
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
391386
while (rclcpp::ok(this->context_) && spinning.load()) {
392387
// Do one item of work.
393388
spin_once_impl(timeout_left);
394389

395-
// Check if the future is set, return SUCCESS if it is.
396-
status = future.wait_for(std::chrono::seconds(0));
397-
if (status == std::future_status::ready) {
390+
if (condition()) {
398391
return FutureReturnCode::SUCCESS;
399392
}
400393
// If the original timeout is < 0, then this is blocking, never TIMEOUT.
@@ -410,10 +403,43 @@ class Executor
410403
timeout_left = std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - now);
411404
}
412405

413-
// The future did not complete before ok() returned false, return INTERRUPTED.
406+
// The condition did not pass before ok() returned false, return INTERRUPTED.
414407
return FutureReturnCode::INTERRUPTED;
415408
}
416409

410+
/// Spin (blocking) for at least the given amount of duration.
411+
/**
412+
* \param[in] duration How long to spin for, which gets passed to Executor::spin_node_once.
413+
*/
414+
template<typename TimeRepT = int64_t, typename TimeT = std::milli>
415+
void
416+
spin_for(std::chrono::duration<TimeRepT, TimeT> timeout duration)
417+
{
418+
(void)spin_until_complete([]() {return false;}, duration);
419+
}
420+
421+
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
422+
/**
423+
* \param[in] future The future to wait on. If this function returns SUCCESS, the future can be
424+
* accessed without blocking (though it may still throw an exception).
425+
* \param[in] timeout Optional timeout parameter, which gets passed to Executor::spin_node_once.
426+
* `-1` is block forever, `0` is non-blocking.
427+
* If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return
428+
* code.
429+
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
430+
*/
431+
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
432+
FutureReturnCode
433+
spin_until_future_complete(
434+
const FutureT & future,
435+
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
436+
{
437+
const auto condition = [&future]() {
438+
return future.wait_for(std::chrono::seconds(0)) == std::future_status::ready;
439+
};
440+
return spin_until_complete(condition, timeout);
441+
}
442+
417443
/// Cancel any running spin* function, causing it to return.
418444
/**
419445
* This function can be called asynchonously from any thread.

rclcpp/include/rclcpp/executors.hpp

Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,48 @@ namespace executors
6767
using rclcpp::executors::MultiThreadedExecutor;
6868
using rclcpp::executors::SingleThreadedExecutor;
6969

70+
/// Spin (blocking) until the conditon is complete, it times out waiting, or rclcpp is interrupted.
71+
/**
72+
* \param[in] executor The executor which will spin the node.
73+
* \param[in] node_ptr The node to spin.
74+
* \param[in] condition The callable condition to wait on.
75+
* \param[in] timeout Optional timeout parameter, which gets passed to
76+
* Executor::spin_node_once.
77+
* `-1` is block forever, `0` is non-blocking.
78+
* If the time spent inside the blocking loop exceeds this timeout, return a `TIMEOUT` return code.
79+
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
80+
*/
81+
template<typename TimeRepT = int64_t, typename TimeT = std::milli>
82+
rclcpp::FutureReturnCode
83+
spin_node_until_complete(
84+
rclcpp::Executor & executor,
85+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
86+
const std::function<bool(void)> & condition,
87+
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
88+
{
89+
// TODO(wjwwood): does not work recursively; can't call spin_node_until_complete
90+
// inside a callback executed by an executor.
91+
executor.add_node(node_ptr);
92+
auto retcode = executor.spin_until_complete(condition, timeout);
93+
executor.remove_node(node_ptr);
94+
return retcode;
95+
}
96+
97+
template<typename NodeT = rclcpp::Node, typename TimeRepT = int64_t, typename TimeT = std::milli>
98+
rclcpp::FutureReturnCode
99+
spin_node_until_complete(
100+
rclcpp::Executor & executor,
101+
std::shared_ptr<NodeT> node_ptr,
102+
const std::function<bool(void)> & condition,
103+
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
104+
{
105+
return rclcpp::executors::spin_node_until_complete(
106+
executor,
107+
node_ptr->get_node_base_interface(),
108+
condition,
109+
timeout);
110+
}
111+
70112
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
71113
/**
72114
* \param[in] executor The executor which will spin the node.
@@ -113,6 +155,27 @@ spin_node_until_future_complete(
113155

114156
} // namespace executors
115157

158+
template<typename TimeRepT = int64_t, typename TimeT = std::milli>
159+
rclcpp::FutureReturnCode
160+
spin_until_complete(
161+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
162+
const std::function<bool(void)> & condition,
163+
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
164+
{
165+
rclcpp::executors::SingleThreadedExecutor executor;
166+
return executors::spin_node_until_complete(executor, node_ptr, condition, timeout);
167+
}
168+
169+
template<typename NodeT = rclcpp::Node, typename TimeRepT = int64_t, typename TimeT = std::milli>
170+
rclcpp::FutureReturnCode
171+
spin_until_complete(
172+
std::shared_ptr<NodeT> node_ptr,
173+
const std::function<bool(void)> & condition,
174+
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
175+
{
176+
return rclcpp::spin_until_complete(node_ptr->get_node_base_interface(), condition, timeout);
177+
}
178+
116179
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
117180
rclcpp::FutureReturnCode
118181
spin_until_future_complete(

rclcpp/include/rclcpp/rclcpp.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,7 @@
6969
* - Executors (responsible for execution of callbacks through a blocking spin):
7070
* - rclcpp::spin()
7171
* - rclcpp::spin_some()
72+
* - rclcpp::spin_until_complete()
7273
* - rclcpp::spin_until_future_complete()
7374
* - rclcpp::executors::SingleThreadedExecutor
7475
* - rclcpp::executors::SingleThreadedExecutor::add_node()

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -220,6 +220,26 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureComplete)
220220
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
221221
}
222222

223+
// Check executor exits immediately if condition is complete.
224+
TYPED_TEST(TestExecutors, testSpinUntilCompleteCallable)
225+
{
226+
using ExecutorType = TypeParam;
227+
ExecutorType executor;
228+
executor.add_node(this->node);
229+
230+
// test success of an immediately completed condition
231+
auto condition = []() {return true;};
232+
233+
// spin_until_complete is expected to exit immediately, but would block up until its
234+
// timeout if the future is not checked before spin_once_impl.
235+
auto start = std::chrono::steady_clock::now();
236+
auto ret = executor.spin_until_complete(condition, 1s);
237+
executor.remove_node(this->node, true);
238+
// Check it didn't reach timeout
239+
EXPECT_GT(500ms, (std::chrono::steady_clock::now() - start));
240+
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
241+
}
242+
223243
// Same test, but uses a shared future.
224244
TYPED_TEST(TestExecutors, testSpinUntilSharedFutureComplete)
225245
{

rclcpp/test/rclcpp/test_executor.cpp

Lines changed: 63 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -283,6 +283,37 @@ TEST_F(TestExecutor, spin_some_elapsed) {
283283
ASSERT_TRUE(timer_called);
284284
}
285285

286+
TEST_F(TestExecutor, spin_for_duration) {
287+
DummyExecutor dummy;
288+
auto node = std::make_shared<rclcpp::Node>("node", "ns");
289+
bool timer_called = false;
290+
auto timer =
291+
node->create_wall_timer(
292+
std::chrono::milliseconds(0), [&]() {
293+
timer_called = true;
294+
});
295+
dummy.add_node(node);
296+
// Wait for the wall timer to have expired.
297+
dummy.spin_for(std::chrono::milliseconds(0));
298+
299+
ASSERT_TRUE(timer_called);
300+
}
301+
302+
TEST_F(TestExecutor, spin_for_longer_timer) {
303+
DummyExecutor dummy;
304+
auto node = std::make_shared<rclcpp::Node>("node", "ns");
305+
bool timer_called = false;
306+
auto timer =
307+
node->create_wall_timer(
308+
std::chrono::seconds(10), [&]() {
309+
timer_called = true;
310+
});
311+
dummy.add_node(node);
312+
dummy.spin_for(std::chrono::milliseconds(5));
313+
314+
ASSERT_FALSE(timer_called);
315+
}
316+
286317
TEST_F(TestExecutor, spin_once_in_spin_once) {
287318
DummyExecutor dummy;
288319
auto node = std::make_shared<rclcpp::Node>("node", "ns");
@@ -391,9 +422,7 @@ TEST_F(TestExecutor, spin_until_future_complete_in_spin_until_future_complete) {
391422
std::future<void> future = promise.get_future();
392423
dummy.spin_until_future_complete(future, std::chrono::milliseconds(1));
393424
} catch (const std::runtime_error & err) {
394-
if (err.what() == std::string(
395-
"spin_until_future_complete() called while already spinning"))
396-
{
425+
if (err.what() == std::string("spin_until_complete() called while already spinning")) {
397426
spin_until_future_complete_in_spin_until_future_complete = true;
398427
}
399428
}
@@ -488,6 +517,37 @@ TEST_F(TestExecutor, spin_until_future_complete_future_already_complete) {
488517
dummy.spin_until_future_complete(future, std::chrono::milliseconds(1)));
489518
}
490519

520+
TEST_F(TestExecutor, spin_until_complete_condition_already_complete) {
521+
DummyExecutor dummy;
522+
auto condition = []() {return true;};
523+
EXPECT_EQ(
524+
rclcpp::FutureReturnCode::SUCCESS,
525+
dummy.spin_until_complete(condition, std::chrono::milliseconds(1)));
526+
}
527+
528+
TEST_F(TestExecutor, spin_until_complete_returns_after_condition) {
529+
DummyExecutor dummy;
530+
auto node = std::make_shared<rclcpp::Node>("node", "ns");
531+
bool spin_called = false;
532+
auto timer =
533+
node->create_wall_timer(
534+
std::chrono::milliseconds(1), [&]() {
535+
spin_called = true;
536+
});
537+
dummy.add_node(node);
538+
// Check that we stop spinning after the condition is ready
539+
const auto condition_delay = std::chrono::milliseconds(10);
540+
const auto start = std::chrono::steady_clock::now();
541+
auto condition = [&]() {return std::chrono::steady_clock::now() - start > condition_delay;};
542+
EXPECT_EQ(
543+
rclcpp::FutureReturnCode::SUCCESS,
544+
dummy.spin_until_complete(condition, std::chrono::seconds(1)));
545+
EXPECT_TRUE(spin_called);
546+
const auto end_delay = std::chrono::steady_clock::now() - start;
547+
EXPECT_GE(end_delay, condition_delay);
548+
EXPECT_LT(end_delay, std::chrono::milliseconds(500));
549+
}
550+
491551
TEST_F(TestExecutor, is_spinning) {
492552
DummyExecutor dummy;
493553
ASSERT_FALSE(dummy.is_spinning());

0 commit comments

Comments
 (0)