diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index 58e6fc5b9c..9c3dcc83e8 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -355,8 +355,8 @@ class Executor std::chrono::duration timeout = std::chrono::duration(-1)) { return spin_until_future_complete_impl(std::chrono::duration_cast( - timeout), [&future] () { - return future.wait_for(std::chrono::seconds(0)); + timeout), [&future] (std::chrono::nanoseconds wait_time) { + return future.wait_for(wait_time); } ); } @@ -406,17 +406,17 @@ class Executor /// Spin (blocking) until the get_future_status returns ready, max_duration is reached, /// or rclcpp is interrupted. /** - * \param[in] get_future_status A function returning the status of a future that is been waited for. * \param[in] max_duration Optional duration parameter, which gets passed to Executor::spin_node_once. * `-1` is block forever, `0` is non-blocking. * If the time spent inside the blocking loop exceeds this timeout, return a TIMEOUT return * code. + * \param[in] wait_for_future A function waiting for a future to become ready. * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`. */ RCLCPP_PUBLIC virtual FutureReturnCode spin_until_future_complete_impl( std::chrono::nanoseconds max_duration, - const std::function & get_future_status); + const std::function & wait_for_future); /// Collect work and execute available work, optionally within a duration. /** diff --git a/rclcpp/src/rclcpp/executor.cpp b/rclcpp/src/rclcpp/executor.cpp index 553b7db9b7..3acbf3a180 100644 --- a/rclcpp/src/rclcpp/executor.cpp +++ b/rclcpp/src/rclcpp/executor.cpp @@ -272,14 +272,14 @@ Executor::spin_node_once_nanoseconds( rclcpp::FutureReturnCode Executor::spin_until_future_complete_impl( std::chrono::nanoseconds timeout, - const std::function & get_future_status) + const std::function & get_future_status) { // TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete // inside a callback executed by an executor. // Check the future before entering the while loop. // If the future is already complete, don't try to spin. - std::future_status status = get_future_status(); + std::future_status status = get_future_status(std::chrono::seconds(0)); if (status == std::future_status::ready) { return FutureReturnCode::SUCCESS; } @@ -301,7 +301,7 @@ rclcpp::FutureReturnCode Executor::spin_until_future_complete_impl( spin_once_impl(timeout_left); // Check if the future is set, return SUCCESS if it is. - status = get_future_status(); + status = get_future_status(std::chrono::seconds(0)); if (status == std::future_status::ready) { return FutureReturnCode::SUCCESS; }