From b030e6388f00cc3e0be7f5461b2ef93ee52e4e75 Mon Sep 17 00:00:00 2001 From: Hubert Liberacki Date: Tue, 29 Mar 2022 00:58:50 +0200 Subject: [PATCH] Introduce executors new spin_for method, replace spin_until_future_complete with spin_until_complete. (#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 --- rclcpp/include/rclcpp/client.hpp | 6 +- rclcpp/include/rclcpp/executor.hpp | 135 ++++++++++++------ rclcpp/include/rclcpp/executors.hpp | 88 ++++++++++-- rclcpp/include/rclcpp/future_return_code.hpp | 2 +- rclcpp/include/rclcpp/rclcpp.hpp | 2 +- rclcpp/src/rclcpp/parameter_client.cpp | 32 ++--- rclcpp/src/rclcpp/time_source.cpp | 2 +- rclcpp/test/benchmark/benchmark_client.cpp | 2 +- rclcpp/test/benchmark/benchmark_executor.cpp | 28 ++-- rclcpp/test/benchmark/benchmark_service.cpp | 2 +- .../test/rclcpp/executors/test_executors.cpp | 75 ++++++---- .../test_static_single_threaded_executor.cpp | 4 +- rclcpp/test/rclcpp/test_executor.cpp | 64 +++++++-- ..._intra_process_manager_with_allocators.cpp | 4 +- rclcpp/test/rclcpp/test_parameter_client.cpp | 38 ++--- rclcpp/test/rclcpp/test_qos_event.cpp | 2 +- rclcpp/test/rclcpp/test_timer.cpp | 4 +- .../test_subscription_topic_statistics.cpp | 6 +- .../benchmark/benchmark_action_client.cpp | 16 +-- .../benchmark/benchmark_action_server.cpp | 12 +- rclcpp_action/test/test_client.cpp | 88 ++++++------ rclcpp_action/test/test_server.cpp | 16 +-- .../test/test_component_manager_api.cpp | 30 ++-- 23 files changed, 413 insertions(+), 245 deletions(-) diff --git a/rclcpp/include/rclcpp/client.hpp b/rclcpp/include/rclcpp/client.hpp index e88fa8a949..9b1522399c 100644 --- a/rclcpp/include/rclcpp/client.hpp +++ b/rclcpp/include/rclcpp/client.hpp @@ -579,11 +579,11 @@ class Client : public ClientBase /// Send a request to the service server. /** * This method returns a `FutureAndRequestId` instance - * that can be passed to Executor::spin_until_future_complete() to + * that can be passed to Executor::spin_until_complete() to * wait until it has been completed. * * If the future never completes, - * e.g. the call to Executor::spin_until_future_complete() times out, + * e.g. the call to Executor::spin_until_complete() times out, * Client::remove_pending_request() must be called to clean the client internal state. * Not doing so will make the `Client` instance to use more memory each time a response is not * received from the service server. @@ -592,7 +592,7 @@ class Client : public ClientBase * auto future = client->async_send_request(my_request); * if ( * rclcpp::FutureReturnCode::TIMEOUT == - * executor->spin_until_future_complete(future, timeout)) + * executor->spin_until_complete(future, timeout)) * { * client->remove_pending_request(future); * // handle timeout diff --git a/rclcpp/include/rclcpp/executor.hpp b/rclcpp/include/rclcpp/executor.hpp index ed2ddc4a0a..68a7eb3f7e 100644 --- a/rclcpp/include/rclcpp/executor.hpp +++ b/rclcpp/include/rclcpp/executor.hpp @@ -26,6 +26,7 @@ #include #include #include +#include #include "rcl/guard_condition.h" #include "rcl/wait.h" @@ -319,6 +320,50 @@ class Executor virtual void spin_once(std::chrono::nanoseconds timeout = std::chrono::nanoseconds(-1)); + /// Spin (blocking) until the condition is complete, it times out waiting, + /// or rclcpp is interrupted. + /** + * \param[in] future The condition which can be callable or future type to wait on. + * If this function returns SUCCESS, the future can be + * accessed without blocking (though it may still throw an exception). + * \param[in] timeout Optional timeout 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. + * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`. + */ + template + FutureReturnCode spin_until_complete( + const Condition & condition, + DurationT timeout = DurationT(-1)) + { + if constexpr (std::is_invocable_v) { + using RetT = std::invoke_result_t; + static_assert( + std::is_same_v, + "Conditional callable has to return boolean type"); + return spin_until_complete_impl(condition, timeout); + } else { + auto checkFuture = [&condition]() { + return condition.wait_for(std::chrono::seconds(0)) == + std::future_status::ready; + }; + return spin_until_complete_impl(checkFuture, timeout); + } + } + + /// spin (blocking) for given amount of duration. + /** + * \param[in] duration gets passed to Executor::spin_node_once, + * spins the executor for given duration. + */ + template + void + spin_for(DurationT duration) + { + (void)spin_until_complete([]() {return false;}, duration); + } + /// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted. /** * \param[in] future The future to wait on. If this function returns SUCCESS, the future can be @@ -330,57 +375,13 @@ class Executor * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`. */ template + [[deprecated("use spin_until_complete(const Condition & condition, DurationT timeout) instead")]] FutureReturnCode spin_until_future_complete( const FutureT & future, std::chrono::duration timeout = std::chrono::duration(-1)) { - // 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 = future.wait_for(std::chrono::seconds(0)); - if (status == std::future_status::ready) { - return FutureReturnCode::SUCCESS; - } - - auto end_time = std::chrono::steady_clock::now(); - std::chrono::nanoseconds timeout_ns = std::chrono::duration_cast( - timeout); - if (timeout_ns > std::chrono::nanoseconds::zero()) { - end_time += timeout_ns; - } - std::chrono::nanoseconds timeout_left = timeout_ns; - - if (spinning.exchange(true)) { - throw std::runtime_error("spin_until_future_complete() called while already spinning"); - } - RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); ); - while (rclcpp::ok(this->context_) && spinning.load()) { - // Do one item of work. - spin_once_impl(timeout_left); - - // Check if the future is set, return SUCCESS if it is. - status = future.wait_for(std::chrono::seconds(0)); - if (status == std::future_status::ready) { - return FutureReturnCode::SUCCESS; - } - // If the original timeout is < 0, then this is blocking, never TIMEOUT. - if (timeout_ns < std::chrono::nanoseconds::zero()) { - continue; - } - // Otherwise check if we still have time to wait, return TIMEOUT if not. - auto now = std::chrono::steady_clock::now(); - if (now >= end_time) { - return FutureReturnCode::TIMEOUT; - } - // Subtract the elapsed time from the original timeout. - timeout_left = std::chrono::duration_cast(end_time - now); - } - - // The future did not complete before ok() returned false, return INTERRUPTED. - return FutureReturnCode::INTERRUPTED; + return spin_until_complete(future, timeout); } /// Cancel any running spin* function, causing it to return. @@ -560,6 +561,48 @@ class Executor virtual void spin_once_impl(std::chrono::nanoseconds timeout); +protected: + // Implementation details, used by spin_until_complete and spin_for. + // Previouse implementation of spin_until_future_complete. + template + FutureReturnCode spin_until_complete_impl(Condition condition, DurationT timeout) + { + auto end_time = std::chrono::steady_clock::now(); + std::chrono::nanoseconds timeout_ns = std::chrono::duration_cast( + timeout); + if (timeout_ns > std::chrono::nanoseconds::zero()) { + end_time += timeout_ns; + } + std::chrono::nanoseconds timeout_left = timeout_ns; + if (spinning.exchange(true)) { + throw std::runtime_error("spin_until_complete() called while already spinning"); + } + RCPPUTILS_SCOPE_EXIT(this->spinning.store(false); ); + while (rclcpp::ok(this->context_) && spinning.load()) { + // Do one item of work. + spin_once_impl(timeout_left); + + if (condition()) { + return FutureReturnCode::SUCCESS; + } + // If the original timeout is < 0, then this is blocking, never TIMEOUT. + if (timeout_ns < std::chrono::nanoseconds::zero()) { + continue; + } + // Otherwise check if we still have time to wait, return TIMEOUT if not. + auto now = std::chrono::steady_clock::now(); + if (now >= end_time) { + return FutureReturnCode::TIMEOUT; + } + // Subtract the elapsed time from the original timeout. + timeout_left = std::chrono::duration_cast(end_time - now); + } + + // The condition did not pass before ok() returned false, return INTERRUPTED. + return FutureReturnCode::INTERRUPTED; + } + +public: typedef std::map> diff --git a/rclcpp/include/rclcpp/executors.hpp b/rclcpp/include/rclcpp/executors.hpp index 36fb0d63cf..1d02a4e233 100644 --- a/rclcpp/include/rclcpp/executors.hpp +++ b/rclcpp/include/rclcpp/executors.hpp @@ -54,6 +54,50 @@ namespace executors using rclcpp::executors::MultiThreadedExecutor; using rclcpp::executors::SingleThreadedExecutor; +/// Spin (blocking) until the conditon is complete, it times out waiting, or rclcpp is interrupted. +/** + * \param[in] executor The executor which will spin the node. + * \param[in] node_ptr The node to spin. + * \param[in] condition The callable or future to wait on. If `SUCCESS`, the condition is safe to + * access after this function + * \param[in] timeout Optional timeout 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. + * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`. + */ +template +rclcpp::FutureReturnCode +spin_node_until_complete( + rclcpp::Executor & executor, + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, + const Condition & condition, + DurationT timeout = DurationT(-1)) +{ + // TODO(wjwwood): does not work recursively; can't call spin_node_until_complete + // inside a callback executed by an executor. + executor.add_node(node_ptr); + auto retcode = executor.spin_until_complete(condition, timeout); + executor.remove_node(node_ptr); + return retcode; +} + +template +rclcpp::FutureReturnCode +spin_node_until_complete( + rclcpp::Executor & executor, + std::shared_ptr node_ptr, + const ConditionT & condition, + DurationT timeout = DurationT(-1)) +{ + return rclcpp::executors::spin_node_until_complete( + executor, + node_ptr->get_node_base_interface(), + condition, + timeout); +} + /// Spin (blocking) until the future is complete, it times out waiting, or rclcpp is interrupted. /** * \param[in] executor The executor which will spin the node. @@ -67,6 +111,9 @@ using rclcpp::executors::SingleThreadedExecutor; * \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`. */ template +[[deprecated("use spin_node_until_complete(Executor &," + "node_interfaces::NodeBaseInterface::SharedPtr," + "const Condition &, DurationT) instead")]] rclcpp::FutureReturnCode spin_node_until_future_complete( rclcpp::Executor & executor, @@ -74,16 +121,13 @@ spin_node_until_future_complete( const FutureT & future, std::chrono::duration timeout = std::chrono::duration(-1)) { - // TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete - // inside a callback executed by an executor. - executor.add_node(node_ptr); - auto retcode = executor.spin_until_future_complete(future, timeout); - executor.remove_node(node_ptr); - return retcode; + return spin_until_complete(executor, node_ptr, future, timeout); } template +[[deprecated("use spin_node_until_complete(Executor &, std::shared_ptr," + "const Condition &, DurationT) instead")]] rclcpp::FutureReturnCode spin_node_until_future_complete( rclcpp::Executor & executor, @@ -91,7 +135,7 @@ spin_node_until_future_complete( const FutureT & future, std::chrono::duration timeout = std::chrono::duration(-1)) { - return rclcpp::executors::spin_node_until_future_complete( + return rclcpp::executors::spin_node_until_complete( executor, node_ptr->get_node_base_interface(), future, @@ -100,7 +144,31 @@ spin_node_until_future_complete( } // namespace executors +template +rclcpp::FutureReturnCode +spin_until_complete( + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, + const Condition & condition, + DurationT timeout = DurationT(-1)) +{ + rclcpp::executors::SingleThreadedExecutor executor; + return executors::spin_node_until_complete(executor, node_ptr, condition, timeout); +} + +template +rclcpp::FutureReturnCode +spin_until_complete( + std::shared_ptr node_ptr, + const Condition & condition, + DurationT timeout = DurationT(-1)) +{ + return rclcpp::spin_until_complete(node_ptr->get_node_base_interface(), condition, timeout); +} + template +[[deprecated("use spin_until_complete(node_interfaces::NodeBaseInterface::SharedPtr," + "const Condition &,DurationT) instead")]] rclcpp::FutureReturnCode spin_until_future_complete( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, @@ -108,18 +176,20 @@ spin_until_future_complete( std::chrono::duration timeout = std::chrono::duration(-1)) { rclcpp::executors::SingleThreadedExecutor executor; - return executors::spin_node_until_future_complete(executor, node_ptr, future, timeout); + return executors::spin_node_until_complete(executor, node_ptr, future, timeout); } template +[[deprecated("use spin_until_complete(std::shared_ptr, const Condition &," + "DurationT) instead")]] rclcpp::FutureReturnCode spin_until_future_complete( std::shared_ptr node_ptr, const FutureT & future, std::chrono::duration timeout = std::chrono::duration(-1)) { - return rclcpp::spin_until_future_complete(node_ptr->get_node_base_interface(), future, timeout); + return rclcpp::spin_until_complete(node_ptr->get_node_base_interface(), future, timeout); } } // namespace rclcpp diff --git a/rclcpp/include/rclcpp/future_return_code.hpp b/rclcpp/include/rclcpp/future_return_code.hpp index 0da67d7f7b..505f68431b 100644 --- a/rclcpp/include/rclcpp/future_return_code.hpp +++ b/rclcpp/include/rclcpp/future_return_code.hpp @@ -23,7 +23,7 @@ namespace rclcpp { -/// Return codes to be used with spin_until_future_complete. +/// Return codes to be used with spin_until_complete. /** * SUCCESS: The future is complete and can be accessed with "get" without blocking. * This does not indicate that the operation succeeded; "get" may still throw an exception. diff --git a/rclcpp/include/rclcpp/rclcpp.hpp b/rclcpp/include/rclcpp/rclcpp.hpp index f1d751ff3f..380a766f5d 100644 --- a/rclcpp/include/rclcpp/rclcpp.hpp +++ b/rclcpp/include/rclcpp/rclcpp.hpp @@ -68,7 +68,7 @@ * - Executors (responsible for execution of callbacks through a blocking spin): * - rclcpp::spin() * - rclcpp::spin_some() - * - rclcpp::spin_until_future_complete() + * - rclcpp::spin_until_complete() * - rclcpp::executors::SingleThreadedExecutor * - rclcpp::executors::SingleThreadedExecutor::add_node() * - rclcpp::executors::SingleThreadedExecutor::spin() diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 38ced0e1a5..c8c4d50f35 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -396,9 +396,9 @@ SyncParametersClient::get_parameters( std::chrono::nanoseconds timeout) { auto f = async_parameters_client_->get_parameters(parameter_names); - using rclcpp::executors::spin_node_until_future_complete; + using rclcpp::executors::spin_node_until_complete; if ( - spin_node_until_future_complete( + spin_node_until_complete( *executor_, node_base_interface_, f, timeout) == rclcpp::FutureReturnCode::SUCCESS) { @@ -424,9 +424,9 @@ SyncParametersClient::describe_parameters( { auto f = async_parameters_client_->describe_parameters(parameter_names); - using rclcpp::executors::spin_node_until_future_complete; + using rclcpp::executors::spin_node_until_complete; rclcpp::FutureReturnCode future = - spin_node_until_future_complete(*executor_, node_base_interface_, f, timeout); + spin_node_until_complete(*executor_, node_base_interface_, f, timeout); if (future == rclcpp::FutureReturnCode::SUCCESS) { return f.get(); } @@ -440,9 +440,9 @@ SyncParametersClient::get_parameter_types( { auto f = async_parameters_client_->get_parameter_types(parameter_names); - using rclcpp::executors::spin_node_until_future_complete; + using rclcpp::executors::spin_node_until_complete; if ( - spin_node_until_future_complete( + spin_node_until_complete( *executor_, node_base_interface_, f, timeout) == rclcpp::FutureReturnCode::SUCCESS) { @@ -458,9 +458,9 @@ SyncParametersClient::set_parameters( { auto f = async_parameters_client_->set_parameters(parameters); - using rclcpp::executors::spin_node_until_future_complete; + using rclcpp::executors::spin_node_until_complete; if ( - spin_node_until_future_complete( + spin_node_until_complete( *executor_, node_base_interface_, f, timeout) == rclcpp::FutureReturnCode::SUCCESS) { @@ -476,9 +476,9 @@ SyncParametersClient::delete_parameters( { auto f = async_parameters_client_->delete_parameters(parameters_names); - using rclcpp::executors::spin_node_until_future_complete; + using rclcpp::executors::spin_node_until_complete; if ( - spin_node_until_future_complete( + spin_node_until_complete( *executor_, node_base_interface_, f, timeout) == rclcpp::FutureReturnCode::SUCCESS) { @@ -494,9 +494,9 @@ SyncParametersClient::load_parameters( { auto f = async_parameters_client_->load_parameters(yaml_filename); - using rclcpp::executors::spin_node_until_future_complete; + using rclcpp::executors::spin_node_until_complete; if ( - spin_node_until_future_complete( + spin_node_until_complete( *executor_, node_base_interface_, f, timeout) == rclcpp::FutureReturnCode::SUCCESS) { @@ -512,9 +512,9 @@ SyncParametersClient::set_parameters_atomically( { auto f = async_parameters_client_->set_parameters_atomically(parameters); - using rclcpp::executors::spin_node_until_future_complete; + using rclcpp::executors::spin_node_until_complete; if ( - spin_node_until_future_complete( + spin_node_until_complete( *executor_, node_base_interface_, f, timeout) == rclcpp::FutureReturnCode::SUCCESS) { @@ -532,9 +532,9 @@ SyncParametersClient::list_parameters( { auto f = async_parameters_client_->list_parameters(parameter_prefixes, depth); - using rclcpp::executors::spin_node_until_future_complete; + using rclcpp::executors::spin_node_until_complete; if ( - spin_node_until_future_complete( + spin_node_until_complete( *executor_, node_base_interface_, f, timeout) == rclcpp::FutureReturnCode::SUCCESS) { diff --git a/rclcpp/src/rclcpp/time_source.cpp b/rclcpp/src/rclcpp/time_source.cpp index 42a9208251..21c42530a6 100644 --- a/rclcpp/src/rclcpp/time_source.cpp +++ b/rclcpp/src/rclcpp/time_source.cpp @@ -384,7 +384,7 @@ class TimeSource::NodeState final [this]() { auto future = cancel_clock_executor_promise_.get_future(); clock_executor_->add_callback_group(clock_callback_group_, node_base_); - clock_executor_->spin_until_future_complete(future); + clock_executor_->spin_until_complete(future); } ); } diff --git a/rclcpp/test/benchmark/benchmark_client.cpp b/rclcpp/test/benchmark/benchmark_client.cpp index 26ee58b633..2a964804e3 100644 --- a/rclcpp/test/benchmark/benchmark_client.cpp +++ b/rclcpp/test/benchmark/benchmark_client.cpp @@ -151,7 +151,7 @@ BENCHMARK_F(ClientPerformanceTest, async_send_request_and_response)(benchmark::S for (auto _ : state) { (void)_; auto future = client->async_send_request(shared_request); - rclcpp::spin_until_future_complete( + rclcpp::spin_until_complete( node->get_node_base_interface(), future, std::chrono::seconds(1)); benchmark::DoNotOptimize(future); benchmark::ClobberMemory(); diff --git a/rclcpp/test/benchmark/benchmark_executor.cpp b/rclcpp/test/benchmark/benchmark_executor.cpp index 652007b589..062f02da60 100644 --- a/rclcpp/test/benchmark/benchmark_executor.cpp +++ b/rclcpp/test/benchmark/benchmark_executor.cpp @@ -219,7 +219,7 @@ BENCHMARK_F( BENCHMARK_F( PerformanceTestExecutorSimple, - static_single_thread_executor_spin_until_future_complete)(benchmark::State & st) + static_single_thread_executor_spin_until_complete)(benchmark::State & st) { rclcpp::executors::StaticSingleThreadedExecutor executor; // test success of an immediately finishing future @@ -228,7 +228,7 @@ BENCHMARK_F( promise.set_value(true); auto shared_future = future.share(); - auto ret = executor.spin_until_future_complete(shared_future, 100ms); + auto ret = executor.spin_until_complete(shared_future, 100ms); if (ret != rclcpp::FutureReturnCode::SUCCESS) { st.SkipWithError(rcutils_get_error_string().str); } @@ -243,7 +243,7 @@ BENCHMARK_F( executor.add_node(node); st.ResumeTiming(); - ret = executor.spin_until_future_complete(shared_future, 100ms); + ret = executor.spin_until_complete(shared_future, 100ms); if (ret != rclcpp::FutureReturnCode::SUCCESS) { st.SkipWithError(rcutils_get_error_string().str); break; @@ -256,7 +256,7 @@ BENCHMARK_F( BENCHMARK_F( PerformanceTestExecutorSimple, - single_thread_executor_spin_node_until_future_complete)(benchmark::State & st) + single_thread_executor_spin_node_until_complete)(benchmark::State & st) { rclcpp::executors::SingleThreadedExecutor executor; // test success of an immediately finishing future @@ -265,7 +265,7 @@ BENCHMARK_F( promise.set_value(true); auto shared_future = future.share(); - auto ret = rclcpp::executors::spin_node_until_future_complete( + auto ret = rclcpp::executors::spin_node_until_complete( executor, node, shared_future, 1s); if (ret != rclcpp::FutureReturnCode::SUCCESS) { st.SkipWithError(rcutils_get_error_string().str); @@ -275,7 +275,7 @@ BENCHMARK_F( for (auto _ : st) { (void)_; - ret = rclcpp::executors::spin_node_until_future_complete( + ret = rclcpp::executors::spin_node_until_complete( executor, node, shared_future, 1s); if (ret != rclcpp::FutureReturnCode::SUCCESS) { st.SkipWithError(rcutils_get_error_string().str); @@ -286,7 +286,7 @@ BENCHMARK_F( BENCHMARK_F( PerformanceTestExecutorSimple, - multi_thread_executor_spin_node_until_future_complete)(benchmark::State & st) + multi_thread_executor_spin_node_until_complete)(benchmark::State & st) { rclcpp::executors::MultiThreadedExecutor executor; // test success of an immediately finishing future @@ -295,7 +295,7 @@ BENCHMARK_F( promise.set_value(true); auto shared_future = future.share(); - auto ret = rclcpp::executors::spin_node_until_future_complete( + auto ret = rclcpp::executors::spin_node_until_complete( executor, node, shared_future, 1s); if (ret != rclcpp::FutureReturnCode::SUCCESS) { st.SkipWithError(rcutils_get_error_string().str); @@ -305,7 +305,7 @@ BENCHMARK_F( for (auto _ : st) { (void)_; - ret = rclcpp::executors::spin_node_until_future_complete( + ret = rclcpp::executors::spin_node_until_complete( executor, node, shared_future, 1s); if (ret != rclcpp::FutureReturnCode::SUCCESS) { st.SkipWithError(rcutils_get_error_string().str); @@ -316,7 +316,7 @@ BENCHMARK_F( BENCHMARK_F( PerformanceTestExecutorSimple, - static_single_thread_executor_spin_node_until_future_complete)(benchmark::State & st) + static_single_thread_executor_spin_node_until_complete)(benchmark::State & st) { rclcpp::executors::StaticSingleThreadedExecutor executor; // test success of an immediately finishing future @@ -329,7 +329,7 @@ BENCHMARK_F( for (auto _ : st) { (void)_; - auto ret = rclcpp::executors::spin_node_until_future_complete( + auto ret = rclcpp::executors::spin_node_until_complete( executor, node, shared_future, 1s); if (ret != rclcpp::FutureReturnCode::SUCCESS) { st.SkipWithError(rcutils_get_error_string().str); @@ -338,7 +338,7 @@ BENCHMARK_F( } } -BENCHMARK_F(PerformanceTestExecutorSimple, spin_until_future_complete)(benchmark::State & st) +BENCHMARK_F(PerformanceTestExecutorSimple, spin_until_complete)(benchmark::State & st) { // test success of an immediately finishing future std::promise promise; @@ -346,7 +346,7 @@ BENCHMARK_F(PerformanceTestExecutorSimple, spin_until_future_complete)(benchmark promise.set_value(true); auto shared_future = future.share(); - auto ret = rclcpp::spin_until_future_complete(node, shared_future, 1s); + auto ret = rclcpp::spin_until_complete(node, shared_future, 1s); if (ret != rclcpp::FutureReturnCode::SUCCESS) { st.SkipWithError(rcutils_get_error_string().str); } @@ -355,7 +355,7 @@ BENCHMARK_F(PerformanceTestExecutorSimple, spin_until_future_complete)(benchmark for (auto _ : st) { (void)_; - ret = rclcpp::spin_until_future_complete(node, shared_future, 1s); + ret = rclcpp::spin_until_complete(node, shared_future, 1s); if (ret != rclcpp::FutureReturnCode::SUCCESS) { st.SkipWithError(rcutils_get_error_string().str); break; diff --git a/rclcpp/test/benchmark/benchmark_service.cpp b/rclcpp/test/benchmark/benchmark_service.cpp index a42723da90..43bc24f303 100644 --- a/rclcpp/test/benchmark/benchmark_service.cpp +++ b/rclcpp/test/benchmark/benchmark_service.cpp @@ -137,7 +137,7 @@ BENCHMARK_F(ServicePerformanceTest, async_send_response)(benchmark::State & stat benchmark::DoNotOptimize(service); benchmark::ClobberMemory(); - rclcpp::spin_until_future_complete(node->get_node_base_interface(), future); + rclcpp::spin_until_complete(node->get_node_base_interface(), future); } if (callback_count == 0) { state.SkipWithError("Service callback was not called"); diff --git a/rclcpp/test/rclcpp/executors/test_executors.cpp b/rclcpp/test/rclcpp/executors/test_executors.cpp index 1fa2cbb4dd..929446c21a 100644 --- a/rclcpp/test/rclcpp/executors/test_executors.cpp +++ b/rclcpp/test/rclcpp/executors/test_executors.cpp @@ -222,7 +222,7 @@ TYPED_TEST(TestExecutors, spinWhileAlreadySpinning) { } // Check executor exits immediately if future is complete. -TYPED_TEST(TestExecutors, testSpinUntilFutureComplete) { +TYPED_TEST(TestExecutors, testSpinUntilCompleteFuture) { using ExecutorType = TypeParam; ExecutorType executor; executor.add_node(this->node); @@ -232,11 +232,30 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureComplete) { std::future future = promise.get_future(); promise.set_value(true); - // spin_until_future_complete is expected to exit immediately, but would block up until its + // spin_until_complete is expected to exit immediately, but would block up until its // timeout if the future is not checked before spin_once_impl. auto start = std::chrono::steady_clock::now(); auto shared_future = future.share(); - auto ret = executor.spin_until_future_complete(shared_future, 1s); + auto ret = executor.spin_until_complete(shared_future, 1s); + executor.remove_node(this->node, true); + // Check it didn't reach timeout + EXPECT_GT(500ms, (std::chrono::steady_clock::now() - start)); + EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); +} + +// Check executor exits immediately if future is complete. +TYPED_TEST(TestExecutors, testSpinUntilCompleteCallable) { + using ExecutorType = TypeParam; + ExecutorType executor; + executor.add_node(this->node); + + // test success of an immediately completed condition + auto condition = []() {return true;}; + + // spin_until_complete is expected to exit immediately, but would block up until its + // timeout if the future is not checked before spin_once_impl. + auto start = std::chrono::steady_clock::now(); + auto ret = executor.spin_until_complete(condition, 1s); executor.remove_node(this->node, true); // Check it didn't reach timeout EXPECT_GT(500ms, (std::chrono::steady_clock::now() - start)); @@ -244,7 +263,7 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureComplete) { } // Same test, but uses a shared future. -TYPED_TEST(TestExecutors, testSpinUntilSharedFutureComplete) { +TYPED_TEST(TestExecutors, testSpinUntilCompleteSharedFuture) { using ExecutorType = TypeParam; ExecutorType executor; executor.add_node(this->node); @@ -254,11 +273,11 @@ TYPED_TEST(TestExecutors, testSpinUntilSharedFutureComplete) { std::future future = promise.get_future(); promise.set_value(true); - // spin_until_future_complete is expected to exit immediately, but would block up until its + // spin_until_complete is expected to exit immediately, but would block up until its // timeout if the future is not checked before spin_once_impl. auto shared_future = future.share(); auto start = std::chrono::steady_clock::now(); - auto ret = executor.spin_until_future_complete(shared_future, 1s); + auto ret = executor.spin_until_complete(shared_future, 1s); executor.remove_node(this->node, true); // Check it didn't reach timeout @@ -267,7 +286,7 @@ TYPED_TEST(TestExecutors, testSpinUntilSharedFutureComplete) { } // For a longer running future that should require several iterations of spin_once -TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteNoTimeout) { +TYPED_TEST(TestExecutors, testSpinUntilCompleteNoTimeout) { using ExecutorType = TypeParam; ExecutorType executor; executor.add_node(this->node); @@ -286,7 +305,7 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteNoTimeout) { // Timeout set to negative for no timeout. std::thread spinner([&]() { - auto ret = executor.spin_until_future_complete(future, -1s); + auto ret = executor.spin_until_complete(future, -1s); EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); executor.remove_node(this->node, true); executor.cancel(); @@ -312,15 +331,15 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteNoTimeout) { spinner.join(); } -// Check spin_until_future_complete timeout works as expected -TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteWithTimeout) { +// Check spin_until_complete timeout works as expected +TYPED_TEST(TestExecutors, testSpinUntilCompleteWithTimeout) { using ExecutorType = TypeParam; ExecutorType executor; executor.add_node(this->node); bool spin_exited = false; - // Needs to run longer than spin_until_future_complete's timeout. + // Needs to run longer than spin_until_complete's timeout. std::future future = std::async( std::launch::async, [&spin_exited]() { @@ -332,7 +351,7 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteWithTimeout) { // Short timeout std::thread spinner([&]() { - auto ret = executor.spin_until_future_complete(future, 1ms); + auto ret = executor.spin_until_complete(future, 1ms); EXPECT_EQ(rclcpp::FutureReturnCode::TIMEOUT, ret); executor.remove_node(this->node, true); spin_exited = true; @@ -482,8 +501,8 @@ TYPED_TEST(TestExecutors, spinSome) { spinner.join(); } -// Check spin_node_until_future_complete with node base pointer -TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodeBasePtr) { +// Check spin_node_until_complete with node base pointer +TYPED_TEST(TestExecutors, testSpinNodeUntilCompleteNodeBasePtr) { using ExecutorType = TypeParam; ExecutorType executor; @@ -492,13 +511,13 @@ TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodeBasePtr) { promise.set_value(true); auto shared_future = future.share(); - auto ret = rclcpp::executors::spin_node_until_future_complete( + auto ret = rclcpp::executors::spin_node_until_complete( executor, this->node->get_node_base_interface(), shared_future, 1s); EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); } -// Check spin_node_until_future_complete with node pointer -TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodePtr) { +// Check spin_node_until_complete with node pointer +TYPED_TEST(TestExecutors, testSpinNodeUntilCompleteNodePtr) { using ExecutorType = TypeParam; ExecutorType executor; @@ -507,13 +526,13 @@ TYPED_TEST(TestExecutors, testSpinNodeUntilFutureCompleteNodePtr) { promise.set_value(true); auto shared_future = future.share(); - auto ret = rclcpp::executors::spin_node_until_future_complete( + auto ret = rclcpp::executors::spin_node_until_complete( executor, this->node, shared_future, 1s); EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); } -// Check spin_until_future_complete can be properly interrupted. -TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteInterrupted) { +// Check spin_until_complete can be properly interrupted. +TYPED_TEST(TestExecutors, testSpinUntilCompleteInterrupted) { using ExecutorType = TypeParam; ExecutorType executor; executor.add_node(this->node); @@ -521,7 +540,7 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteInterrupted) { bool spin_exited = false; // This needs to block longer than it takes to get to the shutdown call below and for - // spin_until_future_complete to return + // spin_until_complete to return std::future future = std::async( std::launch::async, [&spin_exited]() { @@ -533,7 +552,7 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteInterrupted) { // Long timeout std::thread spinner([&spin_exited, &executor, &future]() { - auto ret = executor.spin_until_future_complete(future, 1s); + auto ret = executor.spin_until_complete(future, 1s); EXPECT_EQ(rclcpp::FutureReturnCode::INTERRUPTED, ret); spin_exited = true; }); @@ -555,8 +574,8 @@ TYPED_TEST(TestExecutors, testSpinUntilFutureCompleteInterrupted) { spinner.join(); } -// Check spin_until_future_complete with node base pointer (instantiates its own executor) -TEST(TestExecutors, testSpinUntilFutureCompleteNodeBasePtr) { +// Check spin_until_complete with node base pointer (instantiates its own executor) +TEST(TestExecutors, testSpinUntilCompleteNodeBasePtr) { rclcpp::init(0, nullptr); { @@ -567,7 +586,7 @@ TEST(TestExecutors, testSpinUntilFutureCompleteNodeBasePtr) { promise.set_value(true); auto shared_future = future.share(); - auto ret = rclcpp::spin_until_future_complete( + auto ret = rclcpp::spin_until_complete( node->get_node_base_interface(), shared_future, 1s); EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); } @@ -575,8 +594,8 @@ TEST(TestExecutors, testSpinUntilFutureCompleteNodeBasePtr) { rclcpp::shutdown(); } -// Check spin_until_future_complete with node pointer (instantiates its own executor) -TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr) { +// Check spin_until_complete with node pointer (instantiates its own executor) +TEST(TestExecutors, testSpinUntilCompleteNodePtr) { rclcpp::init(0, nullptr); { @@ -587,7 +606,7 @@ TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr) { promise.set_value(true); auto shared_future = future.share(); - auto ret = rclcpp::spin_until_future_complete(node, shared_future, 1s); + auto ret = rclcpp::spin_until_complete(node, shared_future, 1s); EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret); } diff --git a/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp b/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp index 5ca6c1c25a..4e440f7a5c 100644 --- a/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp +++ b/rclcpp/test/rclcpp/executors/test_static_single_threaded_executor.cpp @@ -135,8 +135,8 @@ TEST_F(TestStaticSingleThreadedExecutor, execute_service) { std::future future = promise.get_future(); EXPECT_EQ( rclcpp::FutureReturnCode::TIMEOUT, - executor.spin_until_future_complete(future, std::chrono::milliseconds(1))); + executor.spin_until_complete(future, std::chrono::milliseconds(1))); executor.remove_node(node); - executor.spin_until_future_complete(future, std::chrono::milliseconds(1)); + executor.spin_until_complete(future, std::chrono::milliseconds(1)); } diff --git a/rclcpp/test/rclcpp/test_executor.cpp b/rclcpp/test/rclcpp/test_executor.cpp index bdbb0a1079..e8ff0410c7 100644 --- a/rclcpp/test/rclcpp/test_executor.cpp +++ b/rclcpp/test/rclcpp/test_executor.cpp @@ -294,6 +294,41 @@ TEST_F(TestExecutor, spin_some_elapsed) { ASSERT_TRUE(timer_called); } +TEST_F(TestExecutor, spin_for_duration) +{ + DummyExecutor dummy; + auto node = std::make_shared("node", "ns"); + bool timer_called = false; + auto timer = + node->create_wall_timer( + std::chrono::milliseconds(10), [&]() { + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + timer_called = true; + }); + dummy.add_node(node); + // Wait for the wall timer to have expired. + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + dummy.spin_for(std::chrono::milliseconds(1)); + + ASSERT_TRUE(timer_called); +} + +TEST_F(TestExecutor, spin_for_longer_timer) +{ + DummyExecutor dummy; + auto node = std::make_shared("node", "ns"); + bool timer_called = false; + auto timer = + node->create_wall_timer( + std::chrono::milliseconds(10), [&]() { + timer_called = true; + }); + dummy.add_node(node); + dummy.spin_for(std::chrono::milliseconds(5)); + + ASSERT_FALSE(timer_called); +} + TEST_F(TestExecutor, spin_once_in_spin_once) { DummyExecutor dummy; auto node = std::make_shared("node", "ns"); @@ -482,22 +517,20 @@ TEST_F(TestExecutor, get_group_by_timer_add_callback_group) { ASSERT_EQ(cb_group.get(), dummy.local_get_group_by_timer(timer).get()); } -TEST_F(TestExecutor, spin_until_future_complete_in_spin_until_future_complete) { +TEST_F(TestExecutor, spin_until_complete_in_spin_until_complete) { DummyExecutor dummy; auto node = std::make_shared("node", "ns"); - bool spin_until_future_complete_in_spin_until_future_complete = false; + bool spin_until_complete_in_spin_until_complete = false; auto timer = node->create_wall_timer( std::chrono::milliseconds(1), [&]() { try { - std::promise promise; - std::future future = promise.get_future(); - dummy.spin_until_future_complete(future, std::chrono::milliseconds(1)); + dummy.spin_for(std::chrono::milliseconds(1)); } catch (const std::runtime_error & err) { if (err.what() == std::string( - "spin_until_future_complete() called while already spinning")) + "spin_until_complete() called while already spinning")) { - spin_until_future_complete_in_spin_until_future_complete = true; + spin_until_complete_in_spin_until_complete = true; } } }); @@ -505,11 +538,9 @@ TEST_F(TestExecutor, spin_until_future_complete_in_spin_until_future_complete) { dummy.add_node(node); // Wait for the wall timer to have expired. std::this_thread::sleep_for(std::chrono::milliseconds(50)); - EXPECT_FALSE(spin_until_future_complete_in_spin_until_future_complete); - std::promise promise; - std::future future = promise.get_future(); - dummy.spin_until_future_complete(future, std::chrono::milliseconds(1)); - EXPECT_TRUE(spin_until_future_complete_in_spin_until_future_complete); + EXPECT_FALSE(spin_until_complete_in_spin_until_complete); + dummy.spin_for(std::chrono::milliseconds(2)); + EXPECT_TRUE(spin_until_complete_in_spin_until_complete); } TEST_F(TestExecutor, spin_node_once_base_interface) { @@ -546,7 +577,7 @@ TEST_F(TestExecutor, spin_node_once_node) { EXPECT_TRUE(spin_called); } -TEST_F(TestExecutor, spin_until_future_complete_future_already_complete) { +TEST_F(TestExecutor, spin_until_complete_condition_already_complete) { DummyExecutor dummy; auto node = std::make_shared("node", "ns"); std::promise promise; @@ -554,7 +585,12 @@ TEST_F(TestExecutor, spin_until_future_complete_future_already_complete) { promise.set_value(); EXPECT_EQ( rclcpp::FutureReturnCode::SUCCESS, - dummy.spin_until_future_complete(future, std::chrono::milliseconds(1))); + dummy.spin_until_complete(future, std::chrono::milliseconds(1))); + + auto condition = []() {return true;}; + EXPECT_EQ( + rclcpp::FutureReturnCode::SUCCESS, + dummy.spin_until_complete(condition, std::chrono::milliseconds(1))); } TEST_F(TestExecutor, is_spinning) { diff --git a/rclcpp/test/rclcpp/test_intra_process_manager_with_allocators.cpp b/rclcpp/test/rclcpp/test_intra_process_manager_with_allocators.cpp index 6d192ca86b..35c43ef3d4 100644 --- a/rclcpp/test/rclcpp/test_intra_process_manager_with_allocators.cpp +++ b/rclcpp/test/rclcpp/test_intra_process_manager_with_allocators.cpp @@ -240,7 +240,7 @@ do_custom_allocator_test( EXPECT_NO_THROW( { publisher->publish(std::move(msg)); - executor.spin_until_future_complete(received_message_future, std::chrono::seconds(10)); + executor.spin_until_complete(received_message_future, std::chrono::seconds(10)); }); EXPECT_EQ(ptr, received_message_future.get().get()); EXPECT_EQ(1u, counter); @@ -249,7 +249,7 @@ do_custom_allocator_test( EXPECT_THROW( { publisher->publish(std::move(msg)); - executor.spin_until_future_complete(received_message_future, std::chrono::seconds(10)); + executor.spin_until_complete(received_message_future, std::chrono::seconds(10)); }, ExpectedExceptionT); } } diff --git a/rclcpp/test/rclcpp/test_parameter_client.cpp b/rclcpp/test/rclcpp/test_parameter_client.cpp index 4cd9e671be..cf69dd8ded 100644 --- a/rclcpp/test/rclcpp/test_parameter_client.cpp +++ b/rclcpp/test/rclcpp/test_parameter_client.cpp @@ -212,7 +212,7 @@ TEST_F(TestParameterClient, async_parameter_get_parameter_types) { std::vector names{"foo"}; std::shared_future> future = asynchronous_client->get_parameter_types(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); ASSERT_TRUE(callback_called); @@ -236,7 +236,7 @@ TEST_F(TestParameterClient, async_parameter_get_parameter_types_allow_undeclared std::vector names{"foo"}; std::shared_future> future = asynchronous_client->get_parameter_types(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node_with_option, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); ASSERT_TRUE(callback_called); @@ -258,7 +258,7 @@ TEST_F(TestParameterClient, async_parameter_get_parameters) { std::vector names{"foo"}; std::shared_future> future = asynchronous_client->get_parameters( names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); ASSERT_TRUE(callback_called); @@ -280,7 +280,7 @@ TEST_F(TestParameterClient, async_parameter_get_parameters_allow_undeclared) { std::vector names{"foo"}; std::shared_future> future = asynchronous_client->get_parameters( names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node_with_option, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); ASSERT_TRUE(callback_called); @@ -306,7 +306,7 @@ TEST_F(TestParameterClient, async_parameter_set_parameters_atomically) { parameters.emplace_back(rclcpp::Parameter("foo")); std::shared_future future = asynchronous_client->set_parameters_atomically(parameters, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); ASSERT_TRUE(callback_called); @@ -328,7 +328,7 @@ TEST_F(TestParameterClient, async_parameter_list_parameters) { std::vector prefixes{"foo"}; std::shared_future future = asynchronous_client->list_parameters(prefixes, 0, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); ASSERT_TRUE(callback_called); @@ -553,7 +553,7 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters) { std::vector names{"none"}; std::shared_future> future = asynchronous_client->describe_parameters(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); ASSERT_TRUE(callback_called); @@ -571,7 +571,7 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters) { std::vector names{"foo"}; std::shared_future> future = asynchronous_client->describe_parameters(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); std::vector parameter_descs = future.get(); @@ -597,7 +597,7 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters) { std::vector names{"foo", "baz"}; std::shared_future> future = asynchronous_client->describe_parameters(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); ASSERT_TRUE(callback_called); @@ -616,7 +616,7 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters) { std::vector names{"baz", "foo"}; std::shared_future> future = asynchronous_client->describe_parameters(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); ASSERT_TRUE(callback_called); @@ -634,7 +634,7 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters) { std::vector names{"foo", "bar"}; std::shared_future> future = asynchronous_client->describe_parameters(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); std::vector parameter_descs = future.get(); @@ -733,7 +733,7 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters_allow_undeclared std::vector names{"none"}; std::shared_future> future = asynchronous_client->describe_parameters(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node_with_option, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); std::vector parameter_descs = future.get(); @@ -758,7 +758,7 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters_allow_undeclared std::vector names{"foo", "baz"}; std::shared_future> future = asynchronous_client->describe_parameters(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node_with_option, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); std::vector parameter_descs = future.get(); @@ -788,7 +788,7 @@ TEST_F(TestParameterClient, async_parameter_describe_parameters_allow_undeclared std::vector names{"baz", "foo"}; std::shared_future> future = asynchronous_client->describe_parameters(names, callback); - auto return_code = rclcpp::spin_until_future_complete( + auto return_code = rclcpp::spin_until_complete( node_with_option, future, std::chrono::milliseconds(100)); ASSERT_EQ(rclcpp::FutureReturnCode::SUCCESS, return_code); std::vector parameter_descs = future.get(); @@ -870,17 +870,17 @@ TEST_F(TestParameterClient, async_parameter_delete_parameters) { std::make_shared(node_with_option); // set parameter auto set_future = asynchronous_client->set_parameters({rclcpp::Parameter("foo", 4)}); - rclcpp::spin_until_future_complete( + rclcpp::spin_until_complete( node_with_option, set_future, std::chrono::milliseconds(100)); ASSERT_EQ(set_future.get()[0].successful, true); // delete one parameter auto delete_future = asynchronous_client->delete_parameters({"foo"}); - rclcpp::spin_until_future_complete( + rclcpp::spin_until_complete( node_with_option, delete_future, std::chrono::milliseconds(100)); ASSERT_EQ(delete_future.get()[0].successful, true); // check that deleted parameter isn't set auto get_future2 = asynchronous_client->get_parameters({"foo"}); - rclcpp::spin_until_future_complete( + rclcpp::spin_until_complete( node_with_option, get_future2, std::chrono::milliseconds(100)); ASSERT_EQ( get_future2.get()[0].get_type(), @@ -918,13 +918,13 @@ TEST_F(TestParameterClient, async_parameter_load_parameters) { const std::string parameters_filepath = ( test_resources_path / "test_node" / "load_parameters.yaml").string(); auto load_future = asynchronous_client->load_parameters(parameters_filepath); - auto result_code = rclcpp::spin_until_future_complete( + auto result_code = rclcpp::spin_until_complete( load_node, load_future, std::chrono::milliseconds(100)); ASSERT_EQ(result_code, rclcpp::FutureReturnCode::SUCCESS); ASSERT_EQ(load_future.get()[0].successful, true); // list parameters auto list_parameters = asynchronous_client->list_parameters({}, 3); - rclcpp::spin_until_future_complete( + rclcpp::spin_until_complete( load_node, list_parameters, std::chrono::milliseconds(100)); ASSERT_EQ(list_parameters.get().names.size(), static_cast(5)); } diff --git a/rclcpp/test/rclcpp/test_qos_event.cpp b/rclcpp/test/rclcpp/test_qos_event.cpp index 221e2bdf0a..26f47c0436 100644 --- a/rclcpp/test/rclcpp/test_qos_event.cpp +++ b/rclcpp/test/rclcpp/test_qos_event.cpp @@ -201,7 +201,7 @@ TEST_F(TestQosEvent, test_default_incompatible_qos_callbacks) // This future won't complete on fastrtps, so just timeout immediately const auto timeout = std::chrono::seconds(10); - ex.spin_until_future_complete(log_msgs_future, timeout); + ex.spin_until_complete(log_msgs_future, timeout); EXPECT_EQ( "New subscription discovered on topic '/ns/test_topic', requesting incompatible QoS. " diff --git a/rclcpp/test/rclcpp/test_timer.cpp b/rclcpp/test/rclcpp/test_timer.cpp index 7a6599dfe4..2fd422b09f 100644 --- a/rclcpp/test/rclcpp/test_timer.cpp +++ b/rclcpp/test/rclcpp/test_timer.cpp @@ -111,13 +111,13 @@ TEST_F(TestTimer, test_is_canceled_reset) // reset shouldn't affect state (not canceled yet) timer->reset(); - EXPECT_LE(timer->time_until_trigger().count(), std::chrono::nanoseconds::max().count()); + EXPECT_LE(timer->time_until_trigger().count(), std::chrono::milliseconds::max().count()); EXPECT_FALSE(timer->is_canceled()); // cancel after reset timer->cancel(); EXPECT_TRUE(timer->is_canceled()); - EXPECT_EQ(timer->time_until_trigger().count(), std::chrono::nanoseconds::max().count()); + EXPECT_EQ(timer->time_until_trigger().count(), std::chrono::milliseconds::max().count()); // reset and cancel timer->reset(); diff --git a/rclcpp/test/rclcpp/topic_statistics/test_subscription_topic_statistics.cpp b/rclcpp/test/rclcpp/topic_statistics/test_subscription_topic_statistics.cpp index ce6887c631..99bf9e4a10 100644 --- a/rclcpp/test/rclcpp/topic_statistics/test_subscription_topic_statistics.cpp +++ b/rclcpp/test/rclcpp/topic_statistics/test_subscription_topic_statistics.cpp @@ -432,7 +432,7 @@ TEST_F(TestSubscriptionTopicStatisticsFixture, test_receive_stats_for_message_no ex.add_node(empty_subscriber); // Spin and get future - ex.spin_until_future_complete( + ex.spin_until_complete( statistics_listener->GetFuture(), kTestTimeout); @@ -497,7 +497,7 @@ TEST_F(TestSubscriptionTopicStatisticsFixture, test_receive_stats_for_message_wi ex.add_node(msg_with_header_subscriber); // Spin and get future - ex.spin_until_future_complete( + ex.spin_until_complete( statistics_listener->GetFuture(), kTestTimeout); @@ -550,7 +550,7 @@ TEST_F(TestSubscriptionTopicStatisticsFixture, test_receive_stats_include_window ex.add_node(msg_with_header_subscriber); // Spin and get future - ex.spin_until_future_complete(statistics_listener->GetFuture(), kTestTimeout); + ex.spin_until_complete(statistics_listener->GetFuture(), kTestTimeout); const auto received_messages = statistics_listener->GetReceivedMessages(); EXPECT_EQ(kNumExpectedMessages, received_messages.size()); diff --git a/rclcpp_action/test/benchmark/benchmark_action_client.cpp b/rclcpp_action/test/benchmark/benchmark_action_client.cpp index 8b11935117..c3d85d4c0c 100644 --- a/rclcpp_action/test/benchmark/benchmark_action_client.cpp +++ b/rclcpp_action/test/benchmark/benchmark_action_client.cpp @@ -194,7 +194,7 @@ BENCHMARK_F(ActionClientPerformanceTest, async_send_goal_rejected)(benchmark::St for (auto _ : state) { (void)_; auto future_goal_handle = client->async_send_goal(goal); - rclcpp::spin_until_future_complete(node, future_goal_handle, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, future_goal_handle, std::chrono::seconds(1)); if (!future_goal_handle.valid()) { state.SkipWithError("Shared future was invalid"); return; @@ -223,7 +223,7 @@ BENCHMARK_F(ActionClientPerformanceTest, async_send_goal_get_accepted_response)( (void)_; // This server's execution is deferred auto future_goal_handle = client->async_send_goal(goal); - rclcpp::spin_until_future_complete(node, future_goal_handle, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, future_goal_handle, std::chrono::seconds(1)); if (!future_goal_handle.valid()) { state.SkipWithError("Shared future was invalid"); @@ -258,7 +258,7 @@ BENCHMARK_F(ActionClientPerformanceTest, async_get_result)(benchmark::State & st auto future_goal_handle = client->async_send_goal(goal); // Action server accepts and defers, so this spin doesn't include result - rclcpp::spin_until_future_complete(node, future_goal_handle, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, future_goal_handle, std::chrono::seconds(1)); if (!future_goal_handle.valid()) { state.SkipWithError("Shared future was invalid"); @@ -276,7 +276,7 @@ BENCHMARK_F(ActionClientPerformanceTest, async_get_result)(benchmark::State & st // Measure how long it takes client to receive the succeeded result auto future_result = client->async_get_result(goal_handle); - rclcpp::spin_until_future_complete(node, future_result, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, future_result, std::chrono::seconds(1)); const auto & wrapped_result = future_result.get(); if (rclcpp_action::ResultCode::SUCCEEDED != wrapped_result.code) { state.SkipWithError("Fibonacci action did not succeed"); @@ -310,12 +310,12 @@ BENCHMARK_F(ActionClientPerformanceTest, async_cancel_goal)(benchmark::State & s auto future_goal_handle = client->async_send_goal(goal); // Action server accepts and defers, so action can be canceled - rclcpp::spin_until_future_complete(node, future_goal_handle, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, future_goal_handle, std::chrono::seconds(1)); auto goal_handle = future_goal_handle.get(); state.ResumeTiming(); auto future_cancel = client->async_cancel_goal(goal_handle); - rclcpp::spin_until_future_complete(node, future_cancel, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, future_cancel, std::chrono::seconds(1)); auto cancel_response = future_cancel.get(); using CancelActionResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response; @@ -345,13 +345,13 @@ BENCHMARK_F(ActionClientPerformanceTest, async_cancel_all_goals)(benchmark::Stat state.PauseTiming(); for (int i = 0; i < num_concurrently_inflight_goals; ++i) { auto future_goal_handle = client->async_send_goal(goal); - rclcpp::spin_until_future_complete(node, future_goal_handle, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, future_goal_handle, std::chrono::seconds(1)); } // Action server accepts and defers, so action can be canceled state.ResumeTiming(); auto future_cancel_all = client->async_cancel_all_goals(); - rclcpp::spin_until_future_complete(node, future_cancel_all, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, future_cancel_all, std::chrono::seconds(1)); auto cancel_response = future_cancel_all.get(); using CancelActionResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response; diff --git a/rclcpp_action/test/benchmark/benchmark_action_server.cpp b/rclcpp_action/test/benchmark/benchmark_action_server.cpp index 6817f86b14..d0eb86c749 100644 --- a/rclcpp_action/test/benchmark/benchmark_action_server.cpp +++ b/rclcpp_action/test/benchmark/benchmark_action_server.cpp @@ -152,7 +152,7 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_accept_goal)(benchmark::S auto client_goal_handle_future = AsyncSendGoalOfOrder(1); state.ResumeTiming(); - rclcpp::spin_until_future_complete(node, client_goal_handle_future); + rclcpp::spin_until_complete(node, client_goal_handle_future); auto goal_handle = client_goal_handle_future.get(); if (rclcpp_action::GoalStatus::STATUS_ACCEPTED != goal_handle->get_status()) { state.SkipWithError("Valid goal was not accepted"); @@ -185,12 +185,12 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_cancel_goal)(benchmark::S auto client_goal_handle_future = AsyncSendGoalOfOrder(1); // This spin completes when the goal has been accepted, but not executed because server // responds with ACCEPT_AND_DEFER - rclcpp::spin_until_future_complete(node, client_goal_handle_future, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, client_goal_handle_future, std::chrono::seconds(1)); auto client_goal_handle = client_goal_handle_future.get(); auto future_cancel = action_client->async_cancel_goal(client_goal_handle); state.ResumeTiming(); - rclcpp::spin_until_future_complete(node, future_cancel, std::chrono::seconds(1)); + rclcpp::spin_until_complete(node, future_cancel, std::chrono::seconds(1)); auto cancel_response = future_cancel.get(); using CancelActionResponse = test_msgs::action::Fibonacci::Impl::CancelGoalService::Response; if (CancelActionResponse::ERROR_NONE != cancel_response->return_code) { @@ -221,7 +221,7 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_execute_goal)(benchmark:: state.PauseTiming(); auto client_goal_handle_future = AsyncSendGoalOfOrder(1); - rclcpp::spin_until_future_complete(node, client_goal_handle_future); + rclcpp::spin_until_complete(node, client_goal_handle_future); auto goal_handle = client_goal_handle_future.get(); if (rclcpp_action::GoalStatus::STATUS_ACCEPTED != goal_handle->get_status()) { state.SkipWithError("Valid goal was not accepted"); @@ -267,7 +267,7 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_set_success)(benchmark::S state.PauseTiming(); auto client_goal_handle_future = AsyncSendGoalOfOrder(goal_order); - rclcpp::spin_until_future_complete(node, client_goal_handle_future); + rclcpp::spin_until_complete(node, client_goal_handle_future); auto goal_handle = client_goal_handle_future.get(); if (rclcpp_action::GoalStatus::STATUS_ACCEPTED != goal_handle->get_status()) { state.SkipWithError("Valid goal was not accepted"); @@ -312,7 +312,7 @@ BENCHMARK_F(ActionServerPerformanceTest, action_server_abort)(benchmark::State & state.PauseTiming(); auto client_goal_handle_future = AsyncSendGoalOfOrder(goal_order); - rclcpp::spin_until_future_complete(node, client_goal_handle_future); + rclcpp::spin_until_complete(node, client_goal_handle_future); auto goal_handle = client_goal_handle_future.get(); if (rclcpp_action::GoalStatus::STATUS_ACCEPTED != goal_handle->get_status()) { state.SkipWithError("Valid goal was not accepted"); diff --git a/rclcpp_action/test/test_client.cpp b/rclcpp_action/test/test_client.cpp index b99aa236bd..b1477c1df4 100644 --- a/rclcpp_action/test/test_client.cpp +++ b/rclcpp_action/test/test_client.cpp @@ -247,7 +247,7 @@ class TestClient : public ::testing::Test } template - void dual_spin_until_future_complete(std::shared_future & future) + void dual_spin_until_complete(std::shared_future & future) { std::future_status status; do { @@ -416,13 +416,13 @@ TEST_F(TestClientAgainstServer, async_send_goal_no_callbacks) ActionGoal bad_goal; bad_goal.order = -5; auto future_goal_handle = action_client->async_send_goal(bad_goal); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); EXPECT_EQ(nullptr, future_goal_handle.get().get()); ActionGoal good_goal; good_goal.order = 5; future_goal_handle = action_client->async_send_goal(good_goal); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); EXPECT_FALSE(goal_handle->is_feedback_aware()); @@ -437,7 +437,7 @@ TEST_F(TestClientAgainstServer, bad_goal_handles) ActionGoal goal; goal.order = 0; auto future_goal_handle = action_client0->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); auto action_client1 = rclcpp_action::create_client(client_node, action_name); @@ -454,14 +454,14 @@ TEST_F(TestClientAgainstServer, async_send_goal_no_callbacks_wait_for_result) ActionGoal goal; goal.order = 5; auto future_goal_handle = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); EXPECT_FALSE(goal_handle->is_feedback_aware()); EXPECT_FALSE(goal_handle->is_result_aware()); auto future_result = action_client->async_get_result(goal_handle); EXPECT_TRUE(goal_handle->is_result_aware()); - dual_spin_until_future_complete(future_result); + dual_spin_until_complete(future_result); auto wrapped_result = future_result.get(); ASSERT_EQ(6ul, wrapped_result.result->sequence.size()); EXPECT_EQ(0, wrapped_result.result->sequence[0]); @@ -477,7 +477,7 @@ TEST_F(TestClientAgainstServer, async_send_goal_no_callbacks_then_invalidate) ActionGoal goal; goal.order = 5; auto future_goal_handle = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); ASSERT_NE(nullptr, goal_handle); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); @@ -511,7 +511,7 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_goal_response_callback_wait ActionGoal bad_goal; bad_goal.order = -1; auto future_goal_handle = action_client->async_send_goal(bad_goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_FALSE(goal_response_received); EXPECT_EQ(nullptr, goal_handle); @@ -521,7 +521,7 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_goal_response_callback_wait ActionGoal goal; goal.order = 4; auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_TRUE(goal_response_received); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); @@ -529,7 +529,7 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_goal_response_callback_wait EXPECT_FALSE(goal_handle->is_result_aware()); auto future_result = action_client->async_get_result(goal_handle); EXPECT_TRUE(goal_handle->is_result_aware()); - dual_spin_until_future_complete(future_result); + dual_spin_until_complete(future_result); auto wrapped_result = future_result.get(); ASSERT_EQ(5u, wrapped_result.result->sequence.size()); EXPECT_EQ(3, wrapped_result.result->sequence.back()); @@ -569,7 +569,7 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_deprecated_goal_response_ca ActionGoal bad_goal; bad_goal.order = -1; auto future_goal_handle = action_client->async_send_goal(bad_goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_FALSE(goal_response_received); EXPECT_EQ(nullptr, goal_handle); @@ -579,7 +579,7 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_deprecated_goal_response_ca ActionGoal goal; goal.order = 4; auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_TRUE(goal_response_received); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); @@ -587,7 +587,7 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_deprecated_goal_response_ca EXPECT_FALSE(goal_handle->is_result_aware()); auto future_result = action_client->async_get_result(goal_handle); EXPECT_TRUE(goal_handle->is_result_aware()); - dual_spin_until_future_complete(future_result); + dual_spin_until_complete(future_result); auto wrapped_result = future_result.get(); ASSERT_EQ(5u, wrapped_result.result->sequence.size()); EXPECT_EQ(3, wrapped_result.result->sequence.back()); @@ -613,14 +613,14 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_feedback_callback_wait_for_ feedback_count++; }; auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); EXPECT_TRUE(goal_handle->is_feedback_aware()); EXPECT_FALSE(goal_handle->is_result_aware()); auto future_result = action_client->async_get_result(goal_handle); EXPECT_TRUE(goal_handle->is_result_aware()); - dual_spin_until_future_complete(future_result); + dual_spin_until_complete(future_result); auto wrapped_result = future_result.get(); ASSERT_EQ(5u, wrapped_result.result->sequence.size()); @@ -649,13 +649,13 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_result_callback_wait_for_re } }; auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); EXPECT_FALSE(goal_handle->is_feedback_aware()); EXPECT_TRUE(goal_handle->is_result_aware()); auto future_result = action_client->async_get_result(goal_handle); - dual_spin_until_future_complete(future_result); + dual_spin_until_complete(future_result); auto wrapped_result = future_result.get(); EXPECT_TRUE(result_callback_received); @@ -671,7 +671,7 @@ TEST_F(TestClientAgainstServer, async_get_result_with_callback) ActionGoal goal; goal.order = 4; auto future_goal_handle = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_NE(goal_handle, nullptr); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); @@ -690,7 +690,7 @@ TEST_F(TestClientAgainstServer, async_get_result_with_callback) result_callback_received = true; } }); - dual_spin_until_future_complete(future_result); + dual_spin_until_complete(future_result); auto wrapped_result = future_result.get(); EXPECT_TRUE(result_callback_received); @@ -706,12 +706,12 @@ TEST_F(TestClientAgainstServer, async_cancel_one_goal) ActionGoal goal; goal.order = 5; auto future_goal_handle = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); auto future_cancel = action_client->async_cancel_goal(goal_handle); - dual_spin_until_future_complete(future_cancel); + dual_spin_until_complete(future_cancel); ActionCancelGoalResponse::SharedPtr cancel_response = future_cancel.get(); EXPECT_EQ(ActionCancelGoalResponse::ERROR_NONE, cancel_response->return_code); } @@ -724,7 +724,7 @@ TEST_F(TestClientAgainstServer, async_cancel_one_goal_with_callback) ActionGoal goal; goal.order = 5; auto future_goal_handle = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_ACCEPTED, goal_handle->get_status()); @@ -742,7 +742,7 @@ TEST_F(TestClientAgainstServer, async_cancel_one_goal_with_callback) cancel_response_received = true; } }); - dual_spin_until_future_complete(future_cancel); + dual_spin_until_complete(future_cancel); auto cancel_response = future_cancel.get(); EXPECT_EQ(ActionCancelGoalResponse::ERROR_NONE, cancel_response->return_code); ASSERT_EQ(1ul, cancel_response->goals_canceling.size()); @@ -758,14 +758,14 @@ TEST_F(TestClientAgainstServer, async_cancel_all_goals) ActionGoal goal; goal.order = 6; auto future_goal_handle0 = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle0); + dual_spin_until_complete(future_goal_handle0); auto goal_handle0 = future_goal_handle0.get(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(clock.get_clock_handle(), RCL_S_TO_NS(2))); goal.order = 8; auto future_goal_handle1 = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle1); + dual_spin_until_complete(future_goal_handle1); auto goal_handle1 = future_goal_handle1.get(); if (goal_handle1->get_goal_id() < goal_handle0->get_goal_id()) { @@ -775,7 +775,7 @@ TEST_F(TestClientAgainstServer, async_cancel_all_goals) ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(clock.get_clock_handle(), RCL_S_TO_NS(3))); auto future_cancel_all = action_client->async_cancel_all_goals(); - dual_spin_until_future_complete(future_cancel_all); + dual_spin_until_complete(future_cancel_all); auto cancel_response = future_cancel_all.get(); EXPECT_EQ(ActionCancelGoalResponse::ERROR_NONE, cancel_response->return_code); @@ -794,14 +794,14 @@ TEST_F(TestClientAgainstServer, async_cancel_all_goals_with_callback) ActionGoal goal; goal.order = 6; auto future_goal_handle0 = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle0); + dual_spin_until_complete(future_goal_handle0); auto goal_handle0 = future_goal_handle0.get(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(clock.get_clock_handle(), RCL_S_TO_NS(2))); goal.order = 8; auto future_goal_handle1 = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle1); + dual_spin_until_complete(future_goal_handle1); auto goal_handle1 = future_goal_handle1.get(); if (goal_handle1->get_goal_id() < goal_handle0->get_goal_id()) { @@ -824,7 +824,7 @@ TEST_F(TestClientAgainstServer, async_cancel_all_goals_with_callback) cancel_callback_received = true; } }); - dual_spin_until_future_complete(future_cancel_all); + dual_spin_until_complete(future_cancel_all); auto cancel_response = future_cancel_all.get(); EXPECT_EQ(ActionCancelGoalResponse::ERROR_NONE, cancel_response->return_code); @@ -844,21 +844,21 @@ TEST_F(TestClientAgainstServer, async_cancel_some_goals) ActionGoal goal; goal.order = 6; auto future_goal_handle0 = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle0); + dual_spin_until_complete(future_goal_handle0); auto goal_handle0 = future_goal_handle0.get(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(clock.get_clock_handle(), RCL_S_TO_NS(2))); goal.order = 8; auto future_goal_handle1 = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle1); + dual_spin_until_complete(future_goal_handle1); auto goal_handle1 = future_goal_handle1.get(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(clock.get_clock_handle(), RCL_S_TO_NS(3))); auto future_cancel_some = action_client->async_cancel_goals_before(goal_handle1->get_goal_stamp()); - dual_spin_until_future_complete(future_cancel_some); + dual_spin_until_complete(future_cancel_some); auto cancel_response = future_cancel_some.get(); EXPECT_EQ(ActionCancelGoalResponse::ERROR_NONE, cancel_response->return_code); @@ -875,14 +875,14 @@ TEST_F(TestClientAgainstServer, async_cancel_some_goals_with_callback) ActionGoal goal; goal.order = 6; auto future_goal_handle0 = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle0); + dual_spin_until_complete(future_goal_handle0); auto goal_handle0 = future_goal_handle0.get(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(clock.get_clock_handle(), RCL_S_TO_NS(2))); goal.order = 8; auto future_goal_handle1 = action_client->async_send_goal(goal); - dual_spin_until_future_complete(future_goal_handle1); + dual_spin_until_complete(future_goal_handle1); auto goal_handle1 = future_goal_handle1.get(); ASSERT_EQ(RCL_RET_OK, rcl_set_ros_time_override(clock.get_clock_handle(), RCL_S_TO_NS(3))); @@ -900,7 +900,7 @@ TEST_F(TestClientAgainstServer, async_cancel_some_goals_with_callback) cancel_callback_received = true; } }); - dual_spin_until_future_complete(future_cancel_some); + dual_spin_until_complete(future_cancel_some); auto cancel_response = future_cancel_some.get(); EXPECT_EQ(ActionCancelGoalResponse::ERROR_NONE, cancel_response->return_code); @@ -935,7 +935,7 @@ TEST_F(TestClientAgainstServer, send_rcl_errors) auto mock = mocking_utils::patch_and_return( "lib:rclcpp_action", rcl_action_send_result_request, RCL_RET_ERROR); auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_EQ(rclcpp_action::GoalStatus::STATUS_UNKNOWN, goal_handle->get_status()); } @@ -944,7 +944,7 @@ TEST_F(TestClientAgainstServer, send_rcl_errors) auto mock = mocking_utils::patch_and_return( "lib:rclcpp_action", rcl_action_send_cancel_request, RCL_RET_ERROR); auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); EXPECT_THROW( action_client->async_cancel_goals_before(goal_handle->get_goal_stamp()), @@ -971,11 +971,11 @@ TEST_F(TestClientAgainstServer, execute_rcl_errors) "lib:rclcpp_action", rcl_action_take_feedback, RCL_RET_ERROR); auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); auto future_result = action_client->async_get_result(goal_handle); EXPECT_THROW( - dual_spin_until_future_complete(future_result), + dual_spin_until_complete(future_result), rclcpp::exceptions::RCLError); } { @@ -986,7 +986,7 @@ TEST_F(TestClientAgainstServer, execute_rcl_errors) auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); EXPECT_THROW( - dual_spin_until_future_complete(future_goal_handle), + dual_spin_until_complete(future_goal_handle), rclcpp::exceptions::RCLError); } { @@ -996,11 +996,11 @@ TEST_F(TestClientAgainstServer, execute_rcl_errors) "lib:rclcpp_action", rcl_action_take_result_response, RCL_RET_ERROR); auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); auto future_result = action_client->async_get_result(goal_handle); EXPECT_THROW( - dual_spin_until_future_complete(future_result), + dual_spin_until_complete(future_result), rclcpp::exceptions::RCLError); } { @@ -1010,12 +1010,12 @@ TEST_F(TestClientAgainstServer, execute_rcl_errors) "lib:rclcpp_action", rcl_action_take_cancel_response, RCL_RET_ERROR); auto future_goal_handle = action_client->async_send_goal(goal, send_goal_ops); - dual_spin_until_future_complete(future_goal_handle); + dual_spin_until_complete(future_goal_handle); auto goal_handle = future_goal_handle.get(); auto future_cancel_some = action_client->async_cancel_goals_before(goal_handle->get_goal_stamp()); EXPECT_THROW( - dual_spin_until_future_complete(future_cancel_some), + dual_spin_until_complete(future_cancel_some), rclcpp::exceptions::RCLError); } } diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index 8687f90fbe..fc5539d8dd 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -59,7 +59,7 @@ class TestServer : public ::testing::Test auto request = std::make_shared(); request->goal_id.uuid = uuid; auto future = client->async_send_request(request); - auto return_code = rclcpp::spin_until_future_complete(node, future, timeout); + auto return_code = rclcpp::spin_until_complete(node, future, timeout); if (rclcpp::FutureReturnCode::SUCCESS == return_code) { return request; } else if (rclcpp::FutureReturnCode::TIMEOUT == return_code) { @@ -82,7 +82,7 @@ class TestServer : public ::testing::Test auto request = std::make_shared(); request->goal_info.goal_id.uuid = uuid; auto future = cancel_client->async_send_request(request); - auto return_code = rclcpp::spin_until_future_complete(node, future, timeout); + auto return_code = rclcpp::spin_until_complete(node, future, timeout); if (rclcpp::FutureReturnCode::SUCCESS == return_code) { return future.get(); } else if (rclcpp::FutureReturnCode::TIMEOUT == return_code) { @@ -264,7 +264,7 @@ TEST_F(TestServer, handle_goal_called) auto future = client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future)); + rclcpp::spin_until_complete(node, future)); ASSERT_EQ(uuid, received_uuid); } @@ -881,7 +881,7 @@ TEST_F(TestServer, get_result) // Wait for the result request to be received ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future)); + rclcpp::spin_until_complete(node, future)); auto response = future.get(); EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status); @@ -897,7 +897,7 @@ TEST_F(TestServer, get_result) future = result_client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future)); + rclcpp::spin_until_complete(node, future)); response = future.get(); EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_UNKNOWN, response->status); @@ -958,7 +958,7 @@ TEST_F(TestServer, get_result_deferred) // Wait for the result request to be received ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node, future)); + rclcpp::spin_until_complete(node, future)); auto response = future.get(); EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status); @@ -1045,7 +1045,7 @@ class TestBasicServer : public TestServer // Wait for the result request to be received ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node_, future)); + rclcpp::spin_until_complete(node_, future)); auto response = future.get(); EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_SUCCEEDED, response->status); @@ -1061,7 +1061,7 @@ class TestBasicServer : public TestServer future = result_client->async_send_request(request); ASSERT_EQ( rclcpp::FutureReturnCode::SUCCESS, - rclcpp::spin_until_future_complete(node_, future)); + rclcpp::spin_until_complete(node_, future)); } protected: diff --git a/rclcpp_components/test/test_component_manager_api.cpp b/rclcpp_components/test/test_component_manager_api.cpp index dfb9db76a2..0d5c3771ed 100644 --- a/rclcpp_components/test/test_component_manager_api.cpp +++ b/rclcpp_components/test/test_component_manager_api.cpp @@ -66,7 +66,7 @@ void test_components_api(bool use_dedicated_executor) request->plugin_name = "test_rclcpp_components::TestComponentFoo"; auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, true); @@ -81,7 +81,7 @@ void test_components_api(bool use_dedicated_executor) request->plugin_name = "test_rclcpp_components::TestComponentBar"; auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, true); @@ -98,7 +98,7 @@ void test_components_api(bool use_dedicated_executor) request->node_name = "test_component_baz"; auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, true); @@ -116,7 +116,7 @@ void test_components_api(bool use_dedicated_executor) request->node_name = "test_component_bing"; auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, true); @@ -132,7 +132,7 @@ void test_components_api(bool use_dedicated_executor) request->plugin_name = "test_rclcpp_components::TestComponent"; auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = future.get(); EXPECT_EQ(result->success, false); @@ -148,7 +148,7 @@ void test_components_api(bool use_dedicated_executor) request->plugin_name = "test_rclcpp_components::TestComponentFoo"; auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = future.get(); EXPECT_EQ(result->success, false); @@ -166,7 +166,7 @@ void test_components_api(bool use_dedicated_executor) request->remap_rules.push_back("alice:=bob"); auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, true); @@ -186,7 +186,7 @@ void test_components_api(bool use_dedicated_executor) request->extra_arguments.push_back(use_intraprocess_comms.to_parameter_msg()); auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, true); @@ -208,7 +208,7 @@ void test_components_api(bool use_dedicated_executor) request->extra_arguments.push_back(use_intraprocess_comms.to_parameter_msg()); auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, false); @@ -230,7 +230,7 @@ void test_components_api(bool use_dedicated_executor) request->extra_arguments.push_back(forward_global_arguments.to_parameter_msg()); auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, true); @@ -251,7 +251,7 @@ void test_components_api(bool use_dedicated_executor) request->extra_arguments.push_back(forward_global_arguments.to_parameter_msg()); auto future = composition_client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, false); @@ -284,7 +284,7 @@ void test_components_api(bool use_dedicated_executor) { auto request = std::make_shared(); auto future = client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = future.get(); auto result_node_names = result->full_node_names; @@ -322,7 +322,7 @@ void test_components_api(bool use_dedicated_executor) request->unique_id = 1; auto future = client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, true); @@ -334,7 +334,7 @@ void test_components_api(bool use_dedicated_executor) request->unique_id = 1; auto future = client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. auto result = future.get(); EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); EXPECT_EQ(result->success, false); @@ -353,7 +353,7 @@ void test_components_api(bool use_dedicated_executor) { auto request = std::make_shared(); auto future = client->async_send_request(request); - auto ret = exec->spin_until_future_complete(future, 5s); // Wait for the result. + auto ret = exec->spin_until_complete(future, 5s); // Wait for the result. EXPECT_EQ(ret, rclcpp::FutureReturnCode::SUCCESS); auto result = future.get(); auto result_node_names = result->full_node_names;