ROS2 async request in services: how do they work?

Hi,
I am trying to use the services asynchronously. According to what I read in 5 days basics C++ tutorial, and the example:

  auto result_future = client_->async_send_request(
  request, std::bind(&ServiceClient::response_callback, this,
  std::placeholders::_1));
  RCLCPP_INFO_STREAM(this->get_logger(), std::string("async_send_request ")
                                               << (this->now()).nanoseconds());
}

void response_callback(rclcpp::Client<std_srvs::srv::Empty>::SharedFuture future) 
{
  RCLCPP_INFO_STREAM(this->get_logger(), std::string("response_callback ")
                                               << (this->now()).nanoseconds());
  auto status = future.wait_for(1s);
  if (status == std::future_status::ready) {
    RCLCPP_INFO(this->get_logger(), "Result: success");
    service_done_ = true;
  } else {
    RCLCPP_INFO(this->get_logger(), "Service In-Progress...");
  }
}

** put special focus in the line auto status = future.wait_for(1s);

My initial thinks were that: okay, when I send an async request, there should be some way of knowing if I have not received a response after a timeout. So I though:

  • maybe async_send_request allows to specify a timeout. But I checked ros2 documentation and it doesn’t.
  • Then, I though: it might is because response_callback executes immediately after async_send_request. And that’s why you have with this future.wait_for(1s) line in the response_callback to evaluate if you received response after a timeout or not.

So, if my theory was right, response_callback was gonna be executed even if service is not available. I tried, but response_callback was never executed.

Then, I though: okay, maybe this does not worked because response_callback is executed after doing the async_send_request, once service server ACCEPTS the request. So, if my theory was right, response_callback was gonna be executed even if service sleeps for 1000 seconds inside the call. I tried, but response_callback was never executed.

So, in summary, I see that the only possibility of executing that callback is when you receive a response. And you dont have any option (from the own ros2 framework) of knowing that you did not receive any response.

I tried all this stuff with several configurations of callback groups (and always with multithreaded executor).

Can someone help me with this? I would like to know if I am right, or if I am wrong and there exist an easy way to know that I have not received any response after a timeout when I do an async request

Hello @daniel.ruiz ,

Very interesting observations, let me try to clarify this to you. Yes, it is possible to know if you don’t receive any response.

Asynchronous calls work like this, as per the official documentation: An asynchronous client will immediately return future , a value that indicates whether the call and response is finished (not the value of the response itself), after sending a request to a service.

Therefore, you can check this future to see if there’s a response or not. It would be like this:

auto result_future = client_->async_send_request(
        request, std::bind(&ServiceClient::response_callback, this,
                           std::placeholders::_1));

// Now check for the response after a timeout of 5 seconds
auto status = result_future.wait_for(5s);

if (status != std::future_status::ready) {

  RCLCPP_WARN(this->get_logger(),
                  "Timeout exceeded: did not receive a response within 5s.");
}

The confusion here, I believe, is that this needs to be checked outside the response_callback function. Why? Because the response_callback will be triggered when there is already a response. I see this is not clear at all in our notes, so we will work to improve this part.

I can send you a full example if needed for further clarification.

Best,

First of all, thank you so much for your response.

Totally understood, but then:
How is it possible to achieve the behavior that I comment, that is to say, that the “thread” where I call the service does not get stuck waiting the timeout of the service (in the case you showed me, the wait_for of the future)? Would it be necessary to create a specific thread to handle with this if I want this behavior?

Hello @daniel.ruiz ,

To prevent blocking the thread, you can just remove the wait_for() call and rely solely on the response_callback to handle the service response asynchronously.

Best,

Yes yes, what I mean or what I wanted let’s say is to know a way of being able to handle not only the response but also to manage a timeout if it takes more than X seconds, but in a asynchronous way.

I though that maybe there exists something, that’s why I asked at the beginning. But according to your answers it seems that the only way is with C++ threads or something similar.

Oh I understand. Yes, you could achieve something like that by using a MultiThreadedExecutor and a Reentrant Callback Group, for instance. It would be something like this:

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/timer.hpp"
#include "std_srvs/srv/empty.hpp"

#include <chrono>
#include <cstdlib>
#include <future>
#include <memory>

using namespace std::chrono_literals;

class ServiceClient : public rclcpp::Node {
private:
  rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_;
  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::CallbackGroup::SharedPtr callback_group_;
  bool service_done_ = false;
  bool service_called_ = false;

  void timer_callback() {

    if (!service_called_) {
      RCLCPP_INFO(this->get_logger(), "Send Async Request");
      send_async_request();
    } else {
      RCLCPP_INFO(this->get_logger(), "Timer Callback Executed");
    }
  }

  void send_async_request() {
    while (!client_->wait_for_service(1s)) {
      if (!rclcpp::ok()) {
        RCLCPP_ERROR(
            this->get_logger(),
            "Client interrupted while waiting for service. Terminating...");
        return;
      }
      RCLCPP_INFO(this->get_logger(),
                  "Service Unavailable. Waiting for Service...");
    }

    auto request = std::make_shared<std_srvs::srv::Empty::Request>();
    auto result_future = client_->async_send_request(
        request, std::bind(&ServiceClient::response_callback, this,
                           std::placeholders::_1));
    service_called_ = true;

    // Now check for the response after a timeout of 4 seconds
    auto status = result_future.wait_for(4s);

    if (status != std::future_status::ready) {

      RCLCPP_WARN(this->get_logger(), "Response not ready yet. Exiting");
      rclcpp::shutdown();
    }
  }

  void
  response_callback(rclcpp::Client<std_srvs::srv::Empty>::SharedFuture future) {

    // Get response value
    // auto response = future.get();
    RCLCPP_INFO(this->get_logger(), "Response: success");
    service_done_ = true;
  }

public:
  ServiceClient() : Node("service_client") {
    callback_group_ =
        this->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
    client_ = this->create_client<std_srvs::srv::Empty>("moving_test");
    timer_ = this->create_wall_timer(
        1s, std::bind(&ServiceClient::timer_callback, this), callback_group_);
  }

  bool is_service_done() const { return this->service_done_; }
};

int main(int argc, char *argv[]) {
  rclcpp::init(argc, argv);
  rclcpp::executors::MultiThreadedExecutor executor;
  auto service_client = std::make_shared<ServiceClient>();
  executor.add_node(service_client);
  while (rclcpp::ok() && !service_client->is_service_done()) {
    executor.spin();
  }

  rclcpp::shutdown();
  return 0;
}

In this example code, the timer_callback() will continue to be executed asynchronously with the wait_for(4s). Then, after the 4s have passed without a response, the node will shutdown.

Best,

This topic was automatically closed 5 days after the last reply. New replies are no longer allowed.