Skip to content

Commit 02043c3

Browse files
committed
Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (ros2#1821)
* Introduce spin_for method. * Introduce spin_until_complete. * Deprecate spin_until_future_complete. * Replace usage of deprecated method. * Update unit-tests. Signed-off-by: Hubert Liberacki <[email protected]>
1 parent eac0063 commit 02043c3

23 files changed

+413
-245
lines changed

rclcpp/include/rclcpp/client.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -579,11 +579,11 @@ class Client : public ClientBase
579579
/// Send a request to the service server.
580580
/**
581581
* This method returns a `FutureAndRequestId` instance
582-
* that can be passed to Executor::spin_until_future_complete() to
582+
* that can be passed to Executor::spin_until_complete() to
583583
* wait until it has been completed.
584584
*
585585
* If the future never completes,
586-
* e.g. the call to Executor::spin_until_future_complete() times out,
586+
* e.g. the call to Executor::spin_until_complete() times out,
587587
* Client::remove_pending_request() must be called to clean the client internal state.
588588
* Not doing so will make the `Client` instance to use more memory each time a response is not
589589
* received from the service server.
@@ -592,7 +592,7 @@ class Client : public ClientBase
592592
* auto future = client->async_send_request(my_request);
593593
* if (
594594
* rclcpp::FutureReturnCode::TIMEOUT ==
595-
* executor->spin_until_future_complete(future, timeout))
595+
* executor->spin_until_complete(future, timeout))
596596
* {
597597
* client->remove_pending_request(future);
598598
* // handle timeout

rclcpp/include/rclcpp/executor.hpp

+89-46
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
#include <mutex>
2727
#include <string>
2828
#include <vector>
29+
#include <type_traits>
2930

3031
#include "rcl/guard_condition.h"
3132
#include "rcl/wait.h"
@@ -319,6 +320,50 @@ class Executor
319320
virtual void
320321
spin_once(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1));
321322

323+
/// Spin (blocking) until the condition is complete, it times out waiting,
324+
/// or rclcpp is interrupted.
325+
/**
326+
* \param[in] future The condition which can be callable or future type to wait on.
327+
* If this function returns SUCCESS, the future can be
328+
* accessed without blocking (though it may still throw an exception).
329+
* \param[in] timeout Optional timeout parameter, which gets passed to Executor::spin_node_once.
330+
* `-1` is block forever, `0` is non-blocking.
331+
* If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return
332+
* code.
333+
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
334+
*/
335+
template<typename Condition, typename DurationT = std::chrono::milliseconds>
336+
FutureReturnCode spin_until_complete(
337+
const Condition & condition,
338+
DurationT timeout = DurationT(-1))
339+
{
340+
if constexpr (std::is_invocable_v<Condition>) {
341+
using RetT = std::invoke_result_t<Condition>;
342+
static_assert(
343+
std::is_same_v<bool, RetT>,
344+
"Conditional callable has to return boolean type");
345+
return spin_until_complete_impl(condition, timeout);
346+
} else {
347+
auto checkFuture = [&condition]() {
348+
return condition.wait_for(std::chrono::seconds(0)) ==
349+
std::future_status::ready;
350+
};
351+
return spin_until_complete_impl(checkFuture, timeout);
352+
}
353+
}
354+
355+
/// spin (blocking) for given amount of duration.
356+
/**
357+
* \param[in] duration gets passed to Executor::spin_node_once,
358+
* spins the executor for given duration.
359+
*/
360+
template<typename DurationT>
361+
void
362+
spin_for(DurationT duration)
363+
{
364+
(void)spin_until_complete([]() {return false;}, duration);
365+
}
366+
322367
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
323368
/**
324369
* \param[in] future The future to wait on. If this function returns SUCCESS, the future can be
@@ -330,57 +375,13 @@ class Executor
330375
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
331376
*/
332377
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
378+
[[deprecated("use spin_until_complete(const Condition & condition, DurationT timeout) instead")]]
333379
FutureReturnCode
334380
spin_until_future_complete(
335381
const FutureT & future,
336382
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
337383
{
338-
// TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
339-
// inside a callback executed by an executor.
340-
341-
// Check the future before entering the while loop.
342-
// If the future is already complete, don't try to spin.
343-
std::future_status status = future.wait_for(std::chrono::seconds(0));
344-
if (status == std::future_status::ready) {
345-
return FutureReturnCode::SUCCESS;
346-
}
347-
348-
auto end_time = std::chrono::steady_clock::now();
349-
std::chrono::nanoseconds timeout_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
350-
timeout);
351-
if (timeout_ns > std::chrono::nanoseconds::zero()) {
352-
end_time += timeout_ns;
353-
}
354-
std::chrono::nanoseconds timeout_left = timeout_ns;
355-
356-
if (spinning.exchange(true)) {
357-
throw std::runtime_error("spin_until_future_complete() called while already spinning");
358-
}
359-
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
360-
while (rclcpp::ok(this->context_) && spinning.load()) {
361-
// Do one item of work.
362-
spin_once_impl(timeout_left);
363-
364-
// Check if the future is set, return SUCCESS if it is.
365-
status = future.wait_for(std::chrono::seconds(0));
366-
if (status == std::future_status::ready) {
367-
return FutureReturnCode::SUCCESS;
368-
}
369-
// If the original timeout is < 0, then this is blocking, never TIMEOUT.
370-
if (timeout_ns < std::chrono::nanoseconds::zero()) {
371-
continue;
372-
}
373-
// Otherwise check if we still have time to wait, return TIMEOUT if not.
374-
auto now = std::chrono::steady_clock::now();
375-
if (now >= end_time) {
376-
return FutureReturnCode::TIMEOUT;
377-
}
378-
// Subtract the elapsed time from the original timeout.
379-
timeout_left = std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - now);
380-
}
381-
382-
// The future did not complete before ok() returned false, return INTERRUPTED.
383-
return FutureReturnCode::INTERRUPTED;
384+
return spin_until_complete(future, timeout);
384385
}
385386

386387
/// Cancel any running spin* function, causing it to return.
@@ -560,6 +561,48 @@ class Executor
560561
virtual void
561562
spin_once_impl(std::chrono::nanoseconds timeout);
562563

564+
protected:
565+
// Implementation details, used by spin_until_complete and spin_for.
566+
// Previouse implementation of spin_until_future_complete.
567+
template<typename Condition, typename DurationT>
568+
FutureReturnCode spin_until_complete_impl(Condition condition, DurationT timeout)
569+
{
570+
auto end_time = std::chrono::steady_clock::now();
571+
std::chrono::nanoseconds timeout_ns = std::chrono::duration_cast<std::chrono::nanoseconds>(
572+
timeout);
573+
if (timeout_ns > std::chrono::nanoseconds::zero()) {
574+
end_time += timeout_ns;
575+
}
576+
std::chrono::nanoseconds timeout_left = timeout_ns;
577+
if (spinning.exchange(true)) {
578+
throw std::runtime_error("spin_until_complete() called while already spinning");
579+
}
580+
RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); );
581+
while (rclcpp::ok(this->context_) && spinning.load()) {
582+
// Do one item of work.
583+
spin_once_impl(timeout_left);
584+
585+
if (condition()) {
586+
return FutureReturnCode::SUCCESS;
587+
}
588+
// If the original timeout is < 0, then this is blocking, never TIMEOUT.
589+
if (timeout_ns < std::chrono::nanoseconds::zero()) {
590+
continue;
591+
}
592+
// Otherwise check if we still have time to wait, return TIMEOUT if not.
593+
auto now = std::chrono::steady_clock::now();
594+
if (now >= end_time) {
595+
return FutureReturnCode::TIMEOUT;
596+
}
597+
// Subtract the elapsed time from the original timeout.
598+
timeout_left = std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - now);
599+
}
600+
601+
// The condition did not pass before ok() returned false, return INTERRUPTED.
602+
return FutureReturnCode::INTERRUPTED;
603+
}
604+
605+
public:
563606
typedef std::map<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr,
564607
const rclcpp::GuardCondition *,
565608
std::owner_less<rclcpp::node_interfaces::NodeBaseInterface::WeakPtr>>

rclcpp/include/rclcpp/executors.hpp

+79-9
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,50 @@ namespace executors
5454
using rclcpp::executors::MultiThreadedExecutor;
5555
using rclcpp::executors::SingleThreadedExecutor;
5656

57+
/// Spin (blocking) until the conditon is complete, it times out waiting, or rclcpp is interrupted.
58+
/**
59+
* \param[in] executor The executor which will spin the node.
60+
* \param[in] node_ptr The node to spin.
61+
* \param[in] condition The callable or future to wait on. If `SUCCESS`, the condition is safe to
62+
* access after this function
63+
* \param[in] timeout Optional timeout parameter, which gets passed to
64+
* Executor::spin_node_once.
65+
* `-1` is block forever, `0` is non-blocking.
66+
* If the time spent inside the blocking loop exceeds this timeout, return a `TIMEOUT` return code.
67+
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
68+
*/
69+
template<typename Condition, typename DurationT = std::chrono::milliseconds>
70+
rclcpp::FutureReturnCode
71+
spin_node_until_complete(
72+
rclcpp::Executor & executor,
73+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
74+
const Condition & condition,
75+
DurationT timeout = DurationT(-1))
76+
{
77+
// TODO(wjwwood): does not work recursively; can't call spin_node_until_complete
78+
// inside a callback executed by an executor.
79+
executor.add_node(node_ptr);
80+
auto retcode = executor.spin_until_complete(condition, timeout);
81+
executor.remove_node(node_ptr);
82+
return retcode;
83+
}
84+
85+
template<typename NodeT = rclcpp::Node, typename ConditionT,
86+
typename DurationT = std::chrono::milliseconds>
87+
rclcpp::FutureReturnCode
88+
spin_node_until_complete(
89+
rclcpp::Executor & executor,
90+
std::shared_ptr<NodeT> node_ptr,
91+
const ConditionT & condition,
92+
DurationT timeout = DurationT(-1))
93+
{
94+
return rclcpp::executors::spin_node_until_complete(
95+
executor,
96+
node_ptr->get_node_base_interface(),
97+
condition,
98+
timeout);
99+
}
100+
57101
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
58102
/**
59103
* \param[in] executor The executor which will spin the node.
@@ -67,31 +111,31 @@ using rclcpp::executors::SingleThreadedExecutor;
67111
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
68112
*/
69113
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
114+
[[deprecated("use spin_node_until_complete(Executor &,"
115+
"node_interfaces::NodeBaseInterface::SharedPtr,"
116+
"const Condition &, DurationT) instead")]]
70117
rclcpp::FutureReturnCode
71118
spin_node_until_future_complete(
72119
rclcpp::Executor & executor,
73120
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
74121
const FutureT & future,
75122
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
76123
{
77-
// TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
78-
// inside a callback executed by an executor.
79-
executor.add_node(node_ptr);
80-
auto retcode = executor.spin_until_future_complete(future, timeout);
81-
executor.remove_node(node_ptr);
82-
return retcode;
124+
return spin_until_complete(executor, node_ptr, future, timeout);
83125
}
84126

85127
template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
86128
typename TimeT = std::milli>
129+
[[deprecated("use spin_node_until_complete(Executor &, std::shared_ptr<NodeT>,"
130+
"const Condition &, DurationT) instead")]]
87131
rclcpp::FutureReturnCode
88132
spin_node_until_future_complete(
89133
rclcpp::Executor & executor,
90134
std::shared_ptr<NodeT> node_ptr,
91135
const FutureT & future,
92136
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
93137
{
94-
return rclcpp::executors::spin_node_until_future_complete(
138+
return rclcpp::executors::spin_node_until_complete(
95139
executor,
96140
node_ptr->get_node_base_interface(),
97141
future,
@@ -100,26 +144,52 @@ spin_node_until_future_complete(
100144

101145
} // namespace executors
102146

147+
template<typename Condition, typename DurationT = std::chrono::milliseconds>
148+
rclcpp::FutureReturnCode
149+
spin_until_complete(
150+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
151+
const Condition & condition,
152+
DurationT timeout = DurationT(-1))
153+
{
154+
rclcpp::executors::SingleThreadedExecutor executor;
155+
return executors::spin_node_until_complete<Condition>(executor, node_ptr, condition, timeout);
156+
}
157+
158+
template<typename NodeT = rclcpp::Node, typename Condition,
159+
typename DurationT = std::chrono::milliseconds>
160+
rclcpp::FutureReturnCode
161+
spin_until_complete(
162+
std::shared_ptr<NodeT> node_ptr,
163+
const Condition & condition,
164+
DurationT timeout = DurationT(-1))
165+
{
166+
return rclcpp::spin_until_complete(node_ptr->get_node_base_interface(), condition, timeout);
167+
}
168+
103169
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
170+
[[deprecated("use spin_until_complete(node_interfaces::NodeBaseInterface::SharedPtr,"
171+
"const Condition &,DurationT) instead")]]
104172
rclcpp::FutureReturnCode
105173
spin_until_future_complete(
106174
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
107175
const FutureT & future,
108176
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
109177
{
110178
rclcpp::executors::SingleThreadedExecutor executor;
111-
return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
179+
return executors::spin_node_until_complete<FutureT>(executor, node_ptr, future, timeout);
112180
}
113181

114182
template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
115183
typename TimeT = std::milli>
184+
[[deprecated("use spin_until_complete(std::shared_ptr<NodeT>, const Condition &,"
185+
"DurationT) instead")]]
116186
rclcpp::FutureReturnCode
117187
spin_until_future_complete(
118188
std::shared_ptr<NodeT> node_ptr,
119189
const FutureT & future,
120190
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
121191
{
122-
return rclcpp::spin_until_future_complete(node_ptr->get_node_base_interface(), future, timeout);
192+
return rclcpp::spin_until_complete(node_ptr->get_node_base_interface(), future, timeout);
123193
}
124194

125195
} // namespace rclcpp

rclcpp/include/rclcpp/future_return_code.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
namespace rclcpp
2424
{
2525

26-
/// Return codes to be used with spin_until_future_complete.
26+
/// Return codes to be used with spin_until_complete.
2727
/**
2828
* SUCCESS: The future is complete and can be accessed with "get" without blocking.
2929
* This does not indicate that the operation succeeded; "get" may still throw an exception.

rclcpp/include/rclcpp/rclcpp.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@
6868
* - Executors (responsible for execution of callbacks through a blocking spin):
6969
* - rclcpp::spin()
7070
* - rclcpp::spin_some()
71-
* - rclcpp::spin_until_future_complete()
71+
* - rclcpp::spin_until_complete()
7272
* - rclcpp::executors::SingleThreadedExecutor
7373
* - rclcpp::executors::SingleThreadedExecutor::add_node()
7474
* - rclcpp::executors::SingleThreadedExecutor::spin()

0 commit comments

Comments
 (0)