Skip to content

Commit 351a4c5

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 5c68830 commit 351a4c5

22 files changed

+421
-240
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

+97-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,51 @@ 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 ConditionT, typename DurationT = std::chrono::milliseconds>
336+
FutureReturnCode
337+
spin_until_complete(
338+
const ConditionT & condition,
339+
DurationT timeout = DurationT(-1))
340+
{
341+
if constexpr (std::is_invocable_v<ConditionT>) {
342+
using RetT = std::invoke_result_t<ConditionT>;
343+
static_assert(
344+
std::is_same_v<bool, RetT>,
345+
"Conditional callable has to return boolean type");
346+
return spin_until_complete_impl(condition, timeout);
347+
} else {
348+
auto check_future = [&condition]() {
349+
return condition.wait_for(std::chrono::seconds(0)) ==
350+
std::future_status::ready;
351+
};
352+
return spin_until_complete_impl(check_future, timeout);
353+
}
354+
}
355+
356+
/// Spin (blocking) for at least the given amount of duration.
357+
/**
358+
* \param[in] duration gets passed to Executor::spin_node_once,
359+
* spins the executor for given duration.
360+
*/
361+
template<typename DurationT>
362+
void
363+
spin_for(DurationT duration)
364+
{
365+
(void)spin_until_complete([]() {return false;}, duration);
366+
}
367+
322368
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
323369
/**
324370
* \param[in] future The future to wait on. If this function returns SUCCESS, the future can be
@@ -330,57 +376,13 @@ class Executor
330376
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
331377
*/
332378
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
379+
[[deprecated("use spin_until_complete(const ConditionT & condition, DurationT timeout) instead")]]
333380
FutureReturnCode
334381
spin_until_future_complete(
335382
const FutureT & future,
336383
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
337384
{
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;
385+
return spin_until_complete(future, timeout);
384386
}
385387

386388
/// Cancel any running spin* function, causing it to return.
@@ -560,6 +562,55 @@ class Executor
560562
virtual void
561563
spin_once_impl(std::chrono::nanoseconds timeout);
562564

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

rclcpp/include/rclcpp/executors.hpp

+86-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 ConditionT, 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 ConditionT & 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,34 @@ 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(
115+
"use spin_node_until_complete(Executor &, node_interfaces::NodeBaseInterface::SharedPtr, "
116+
"const ConditionT &, DurationT) instead"
117+
)]]
70118
rclcpp::FutureReturnCode
71119
spin_node_until_future_complete(
72120
rclcpp::Executor & executor,
73121
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
74122
const FutureT & future,
75123
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
76124
{
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;
125+
return spin_until_complete(executor, node_ptr, future, timeout);
83126
}
84127

85128
template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
86129
typename TimeT = std::milli>
130+
[[deprecated(
131+
"use spin_node_until_complete(Executor &, std::shared_ptr<NodeT>, "
132+
"const ConditionT &, DurationT) instead"
133+
)]]
87134
rclcpp::FutureReturnCode
88135
spin_node_until_future_complete(
89136
rclcpp::Executor & executor,
90137
std::shared_ptr<NodeT> node_ptr,
91138
const FutureT & future,
92139
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
93140
{
94-
return rclcpp::executors::spin_node_until_future_complete(
141+
return rclcpp::executors::spin_node_until_complete(
95142
executor,
96143
node_ptr->get_node_base_interface(),
97144
future,
@@ -100,26 +147,56 @@ spin_node_until_future_complete(
100147

101148
} // namespace executors
102149

150+
template<typename ConditionT, typename DurationT = std::chrono::milliseconds>
151+
rclcpp::FutureReturnCode
152+
spin_until_complete(
153+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
154+
const ConditionT & condition,
155+
DurationT timeout = DurationT(-1))
156+
{
157+
rclcpp::executors::SingleThreadedExecutor executor;
158+
return executors::spin_node_until_complete<ConditionT>(executor, node_ptr, condition, timeout);
159+
}
160+
161+
template<typename NodeT = rclcpp::Node, typename ConditionT,
162+
typename DurationT = std::chrono::milliseconds>
163+
rclcpp::FutureReturnCode
164+
spin_until_complete(
165+
std::shared_ptr<NodeT> node_ptr,
166+
const ConditionT & condition,
167+
DurationT timeout = DurationT(-1))
168+
{
169+
return rclcpp::spin_until_complete(node_ptr->get_node_base_interface(), condition, timeout);
170+
}
171+
103172
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
173+
[[deprecated(
174+
"use spin_until_complete(node_interfaces::NodeBaseInterface::SharedPtr, "
175+
"const ConditionT &,DurationT) instead"
176+
)]]
104177
rclcpp::FutureReturnCode
105178
spin_until_future_complete(
106179
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
107180
const FutureT & future,
108181
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
109182
{
110183
rclcpp::executors::SingleThreadedExecutor executor;
111-
return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
184+
return executors::spin_node_until_complete<FutureT>(executor, node_ptr, future, timeout);
112185
}
113186

114187
template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
115188
typename TimeT = std::milli>
189+
[[deprecated(
190+
"use spin_until_complete(std::shared_ptr<NodeT>, const ConditionT &, "
191+
"DurationT) instead"
192+
)]]
116193
rclcpp::FutureReturnCode
117194
spin_until_future_complete(
118195
std::shared_ptr<NodeT> node_ptr,
119196
const FutureT & future,
120197
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
121198
{
122-
return rclcpp::spin_until_future_complete(node_ptr->get_node_base_interface(), future, timeout);
199+
return rclcpp::spin_until_complete(node_ptr->get_node_base_interface(), future, timeout);
123200
}
124201

125202
} // 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)