From 5ac8f1f1b1b25becebccab47f0fa95994e708af0 Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Wed, 20 Mar 2019 13:05:42 -0700 Subject: [PATCH] spin until future complete for async service client Signed-off-by: Karsten Knese --- .../services/add_two_ints_client_async.cpp | 21 +++++++++++-------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/demo_nodes_cpp/src/services/add_two_ints_client_async.cpp b/demo_nodes_cpp/src/services/add_two_ints_client_async.cpp index faf567866..1e4483031 100644 --- a/demo_nodes_cpp/src/services/add_two_ints_client_async.cpp +++ b/demo_nodes_cpp/src/services/add_two_ints_client_async.cpp @@ -24,6 +24,8 @@ #include "example_interfaces/srv/add_two_ints.hpp" using namespace std::chrono_literals; +using ServiceResponseFuture = + rclcpp::Client::SharedFuture; void print_usage() { @@ -41,17 +43,14 @@ class ClientNode : public rclcpp::Node : Node("add_two_ints_client") { client_ = create_client(service_name); - - // Queue an asynchronous service request that will be sent once `spin` is called on the node. - queue_async_request(); } - void queue_async_request() + ServiceResponseFuture queue_async_request() { while (!client_->wait_for_service(1s)) { if (!rclcpp::ok()) { RCLCPP_ERROR(this->get_logger(), "Interrupted while waiting for the service. Exiting."); - return; + return ServiceResponseFuture(); } RCLCPP_INFO(this->get_logger(), "service not available, waiting again..."); } @@ -63,14 +62,12 @@ class ClientNode : public rclcpp::Node // is received. // This way we can return immediately from this method and allow other work to be done by the // executor in `spin` while waiting for the response. - using ServiceResponseFuture = - rclcpp::Client::SharedFuture; auto response_received_callback = [this](ServiceResponseFuture future) { auto result = future.get(); RCLCPP_INFO(this->get_logger(), "Result of add_two_ints: %" PRId64, result->sum); rclcpp::shutdown(); }; - auto future_result = client_->async_send_request(request, response_received_callback); + return client_->async_send_request(request, response_received_callback); } private: @@ -98,7 +95,13 @@ int main(int argc, char ** argv) } auto node = std::make_shared(service_name); - rclcpp::spin(node); + auto service_request_future = node->queue_async_request(); + if (!service_request_future.valid()) { + rclcpp::shutdown(); + return 0; + } + + rclcpp::spin_until_future_complete(node, service_request_future); rclcpp::shutdown(); return 0;