Skip to content

Commit 5b0294f

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 5b0294f

25 files changed

+437
-247
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

+86-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,47 @@ 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, or rclcpp is interrupted.
324+
/**
325+
* \param[in] future The condition which can be callable or future type to wait on. If this function returns SUCCESS, the future can be
326+
* accessed without blocking (though it may still throw an exception).
327+
* \param[in] timeout Optional timeout parameter, which gets passed to Executor::spin_node_once.
328+
* `-1` is block forever, `0` is non-blocking.
329+
* If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return
330+
* code.
331+
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
332+
*/
333+
template<typename Condition, typename DurationT = std::chrono::milliseconds>
334+
FutureReturnCode spin_until_complete(
335+
const Condition & condition,
336+
DurationT timeout = DurationT(-1))
337+
{
338+
if constexpr (std::is_invocable_v<Condition>) {
339+
using RetT = std::invoke_result_t<Condition>;
340+
static_assert(
341+
std::is_same_v<bool, RetT>,
342+
"Conditional callable has to return boolean type");
343+
return spin_until_complete_impl(condition, timeout);
344+
} else {
345+
auto checkFuture = [&condition]() {
346+
return condition.wait_for(std::chrono::seconds(0)) ==
347+
std::future_status::ready;
348+
};
349+
return spin_until_complete_impl(checkFuture, timeout);
350+
}
351+
}
352+
353+
/// spin (blocking) for given amount of duration.
354+
/**
355+
* \param[in] duration gets passed to Executor::spin_node_once, and spins the executor for given duration.
356+
*/
357+
template<typename DurationT>
358+
void
359+
spin_for(DurationT duration)
360+
{
361+
(void)spin_until_complete([]() {return false;}, duration);
362+
}
363+
322364
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
323365
/**
324366
* \param[in] future The future to wait on. If this function returns SUCCESS, the future can be
@@ -330,57 +372,13 @@ class Executor
330372
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
331373
*/
332374
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
375+
[[deprecated("use spin_until_complete(const Condition & condition, DurationT timeout) instead")]]
333376
FutureReturnCode
334377
spin_until_future_complete(
335378
const FutureT & future,
336379
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
337380
{
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;
381+
return spin_until_complete(future, timeout);
384382
}
385383

386384
/// Cancel any running spin* function, causing it to return.
@@ -560,6 +558,48 @@ class Executor
560558
virtual void
561559
spin_once_impl(std::chrono::nanoseconds timeout);
562560

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

rclcpp/include/rclcpp/executors.hpp

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

57+
// TODO(hliberacki): add documentation
58+
// template<typename DurationT>
59+
// void
60+
// spin_for(
61+
// rclcpp::Executor & executor,
62+
// rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
63+
// DurationT timeout)
64+
// {
65+
// executor.add_node(node_ptr);
66+
// auto retcode = executor.spin_for(timeout);
67+
// executor.remove_node(node_ptr);
68+
// return retcode;
69+
// }
70+
71+
// TODO(hliberacki): add documentation
72+
// template<typename NodeT = rclcpp::Node, typename DurationT>
73+
// void
74+
// spin_node_for(
75+
// rclcpp::Executor & executor,
76+
// std::shared_ptr<NodeT> node_ptr,
77+
// rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
78+
// DurationT timeout)
79+
// {
80+
// executor.add_node(node_ptr);
81+
// auto retcode = executor.spin_for(timeout);
82+
// executor.remove_node(node_ptr);
83+
// return retcode;
84+
// }
85+
86+
87+
/// Spin (blocking) until the conditon is complete, it times out waiting, or rclcpp is interrupted.
88+
/**
89+
* \param[in] executor The executor which will spin the node.
90+
* \param[in] node_ptr The node to spin.
91+
* \param[in] condition The callable or future to wait on. If `SUCCESS`, the condition is safe to
92+
* access after this function
93+
* \param[in] timeout Optional timeout parameter, which gets passed to
94+
* Executor::spin_node_once.
95+
* `-1` is block forever, `0` is non-blocking.
96+
* If the time spent inside the blocking loop exceeds this timeout, return a `TIMEOUT` return code.
97+
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
98+
*/
99+
template<typename Condition, typename DurationT = std::chrono::milliseconds>
100+
rclcpp::FutureReturnCode
101+
spin_node_until_complete(
102+
rclcpp::Executor & executor,
103+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
104+
const Condition & condition,
105+
DurationT timeout = DurationT(-1))
106+
{
107+
// TODO(wjwwood): does not work recursively; can't call spin_node_until_complete
108+
// inside a callback executed by an executor.
109+
executor.add_node(node_ptr);
110+
auto retcode = executor.spin_until_complete(condition, timeout);
111+
executor.remove_node(node_ptr);
112+
return retcode;
113+
}
114+
115+
template<typename NodeT = rclcpp::Node, typename ConditionT,
116+
typename DurationT = std::chrono::milliseconds>
117+
rclcpp::FutureReturnCode
118+
spin_node_until_complete(
119+
rclcpp::Executor & executor,
120+
std::shared_ptr<NodeT> node_ptr,
121+
const ConditionT & condition,
122+
DurationT timeout = DurationT(-1))
123+
{
124+
return rclcpp::executors::spin_node_until_complete(
125+
executor,
126+
node_ptr->get_node_base_interface(),
127+
condition,
128+
timeout);
129+
}
130+
57131
/// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted.
58132
/**
59133
* \param[in] executor The executor which will spin the node.
@@ -67,31 +141,28 @@ using rclcpp::executors::SingleThreadedExecutor;
67141
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
68142
*/
69143
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
144+
[[deprecated("use spin_node_until_complete(Executor &, node_interfaces::NodeBaseInterface::SharedPtr, const Condition &, DurationT) instead")]]
70145
rclcpp::FutureReturnCode
71146
spin_node_until_future_complete(
72147
rclcpp::Executor & executor,
73148
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
74149
const FutureT & future,
75150
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
76151
{
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;
152+
return spin_until_complete(executor, node_ptr, future, timeout);
83153
}
84154

85155
template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
86156
typename TimeT = std::milli>
157+
[[deprecated("use spin_node_until_complete(Executor &, std::shared_ptr<NodeT>, const Condition &, DurationT) instead")]]
87158
rclcpp::FutureReturnCode
88159
spin_node_until_future_complete(
89160
rclcpp::Executor & executor,
90161
std::shared_ptr<NodeT> node_ptr,
91162
const FutureT & future,
92163
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
93164
{
94-
return rclcpp::executors::spin_node_until_future_complete(
165+
return rclcpp::executors::spin_node_until_complete(
95166
executor,
96167
node_ptr->get_node_base_interface(),
97168
future,
@@ -100,26 +171,50 @@ spin_node_until_future_complete(
100171

101172
} // namespace executors
102173

174+
template<typename Condition, typename DurationT = std::chrono::milliseconds>
175+
rclcpp::FutureReturnCode
176+
spin_until_complete(
177+
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
178+
const Condition & condition,
179+
DurationT timeout = DurationT(-1))
180+
{
181+
rclcpp::executors::SingleThreadedExecutor executor;
182+
return executors::spin_node_until_complete<Condition>(executor, node_ptr, condition, timeout);
183+
}
184+
185+
template<typename NodeT = rclcpp::Node, typename Condition,
186+
typename DurationT = std::chrono::milliseconds>
187+
rclcpp::FutureReturnCode
188+
spin_until_complete(
189+
std::shared_ptr<NodeT> node_ptr,
190+
const Condition & condition,
191+
DurationT timeout = DurationT(-1))
192+
{
193+
return rclcpp::spin_until_complete(node_ptr->get_node_base_interface(), condition, timeout);
194+
}
195+
103196
template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::milli>
197+
[[deprecated("use spin_until_complete(node_interfaces::NodeBaseInterface::SharedPtr, const Condition &, DurationT) instead")]]
104198
rclcpp::FutureReturnCode
105199
spin_until_future_complete(
106200
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
107201
const FutureT & future,
108202
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
109203
{
110204
rclcpp::executors::SingleThreadedExecutor executor;
111-
return executors::spin_node_until_future_complete<FutureT>(executor, node_ptr, future, timeout);
205+
return executors::spin_node_until_complete<FutureT>(executor, node_ptr, future, timeout);
112206
}
113207

114208
template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = int64_t,
115209
typename TimeT = std::milli>
210+
[[deprecated("use spin_until_complete(std::shared_ptr<NodeT>, const Condition &, DurationT) instead")]]
116211
rclcpp::FutureReturnCode
117212
spin_until_future_complete(
118213
std::shared_ptr<NodeT> node_ptr,
119214
const FutureT & future,
120215
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
121216
{
122-
return rclcpp::spin_until_future_complete(node_ptr->get_node_base_interface(), future, timeout);
217+
return rclcpp::spin_until_complete(node_ptr->get_node_base_interface(), future, timeout);
123218
}
124219

125220
} // 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()

rclcpp/include/rclcpp/wait_set_policies/sequential_synchronization.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -203,7 +203,7 @@ class SequentialSynchronization : public detail::SynchronizationPolicyCommon
203203
std::shared_ptr<rclcpp::Waitable> && waitable,
204204
std::shared_ptr<void> && associated_entity,
205205
std::function<
206-
void(std::shared_ptr<rclcpp::Waitable>&&, std::shared_ptr<void> &&)
206+
void(std::shared_ptr<rclcpp::Waitable>&&, std::shared_ptr<void>&&)
207207
> add_waitable_function)
208208
{
209209
// Explicitly no thread synchronization.

rclcpp/include/rclcpp/wait_set_policies/thread_safe_synchronization.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -216,7 +216,7 @@ class ThreadSafeSynchronization : public detail::SynchronizationPolicyCommon
216216
std::shared_ptr<rclcpp::Waitable> && waitable,
217217
std::shared_ptr<void> && associated_entity,
218218
std::function<
219-
void(std::shared_ptr<rclcpp::Waitable>&&, std::shared_ptr<void> &&)
219+
void(std::shared_ptr<rclcpp::Waitable>&&, std::shared_ptr<void>&&)
220220
> add_waitable_function)
221221
{
222222
using rclcpp::wait_set_policies::detail::WritePreferringReadWriteLock;

0 commit comments

Comments
 (0)