Skip to content

Commit da85eb0

Browse files
Janosch MachowinskiJanosch Machowinski
authored andcommitted
docs: added doc string for spin_until_future_complete_impl
Signed-off-by: Janosch Machowinski <[email protected]>
1 parent 2ebcb49 commit da85eb0

File tree

1 file changed

+11
-0
lines changed

1 file changed

+11
-0
lines changed

rclcpp/include/rclcpp/executor.hpp

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -403,6 +403,17 @@ class Executor
403403
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node,
404404
std::chrono::nanoseconds timeout);
405405

406+
/// Spin (blocking) until the get_future_status returns ready, max_duration is reached,
407+
/// or rclcpp is interrupted.
408+
/**
409+
* \param[in] get_future_status A function returning the status of a future that is been waited for.
410+
* \param[in] max_duration Optional duration parameter, which gets passed to Executor::spin_node_once.
411+
* `-1` is block forever, `0` is non-blocking.
412+
* If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return
413+
* code.
414+
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
415+
*/
416+
RCLCPP_PUBLIC
406417
virtual FutureReturnCode spin_until_future_complete_impl(
407418
std::chrono::nanoseconds max_duration,
408419
const std::function<std::future_status ()> & get_future_status);

0 commit comments

Comments
 (0)