ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
4

[ROS2] How to implement a sync service client in a node?

asked 2020-02-04 15:43:38 -0500

mschickler gravatar image

In ROS1, it was possible to make a (synchronous) service call from a callback.

In ROS2, in a derived node class, if I do the following:

  1. create a service client using "create_client"
  2. within a callback function (e.g. a timer callback) call async_send_request() on the client and then:
  3. call get() on the future that is returned

It will block forever. Instead, I must register a callback when I call async_send_request() in order to handle the response.

An async design does have its advantages, so I am wondering, is it the intent of ROS2 to force asynchronous service message handling in a node or is there a way to do a sync call that I haven't uncovered yet?

edit retag flag offensive close merge delete

Comments

Hi, I'm having the same trouble. I want to not use spin_until_future_complete in my code, because I'm already spinning the node outside of my class. I tried to use wait/wait_for/wait_until on the future, but they all never return and block forever as you described. So the only way is to use a callback? Or have you found another possibility in the meantime?

MrCheesecake gravatar image MrCheesecake  ( 2020-06-05 09:33:46 -0500 )edit
1

@MrCheesecake, see the answer I just posted about how you can get the service response in a synchronous way.

jdlangs gravatar image jdlangs  ( 2020-06-08 13:27:40 -0500 )edit

This is a problem for me as well I asked the same question on github https://github.com/ros2/rclpy/issues/567. Does somebody have python example? That would help me allot

vissermatthijs gravatar image vissermatthijs  ( 2020-06-08 14:11:58 -0500 )edit

@jdlangs thanks for your answer, do you have a example or explanation on how to use callbackgroups. There is not much about this topic out there.
So when I use a callbackgroup of type Reentrant future.get() and future.wait() will work?
Because now they don't (also with MultiThreadedExecutor) .

MrCheesecake gravatar image MrCheesecake  ( 2020-06-10 07:13:28 -0500 )edit
1

@MrCheesecake I just edited my answer to include a full standalone example that demonstrates how to do it.

jdlangs gravatar image jdlangs  ( 2020-06-12 11:00:40 -0500 )edit

4 Answers

Sort by ยป oldest newest most voted
1

answered 2020-02-04 16:20:45 -0500

You're right, this is something I also would like as well. Dealing with all the async stuff for a simple sync application where I'm willing to wait makes the application-level code less clean.

I think your best bet right now is to create a sync_service wrapper to deal with all the async and waiting for you. Then you can use that in your code to interact with it like a synchronous operation.

Right now, that's not "batteries included".

edit flag offensive delete link more
5

answered 2020-06-08 13:26:59 -0500

jdlangs gravatar image

updated 2020-06-12 10:59:12 -0500

This has been a major pain point for me when porting a big ROS1 code base that made synchronous service calls all the time deep inside libraries. My preferred solution to this is setting up the node and client so that the service response arrives on another thread. Then the code calling the service can just do future.get() or future.wait() to wait for the response. You need to:

In general I try to do this and avoid use of spin_until_future_complete whereever possible because I don't want my internal application logic coupled with the spinning/execution of my node. Maybe we'll get some API updates in a future release that makes this easier, especially with having to handle callback group objects explicitly.

Edit: Including a full standalone example to clearly show how to do this. Here a node calls a service advertised by the same node from within the callback of a different service.

#include <rclcpp/rclcpp.hpp>
#include <std_srvs/srv/trigger.hpp>

class TwoSrvs : public rclcpp::Node
{
public:
    TwoSrvs() : Node("two_srvs")
    {
      callback_group_ = this->create_callback_group(rclcpp::callback_group::CallbackGroupType::Reentrant);

      outer_srv_ = this->create_service<std_srvs::srv::Trigger>("outer_srv",
          std::bind(&TwoSrvs::outer_cb, this, std::placeholders::_1, std::placeholders::_2),
          ::rmw_qos_profile_default,
          callback_group_);

      inner_srv_ = this->create_service<std_srvs::srv::Trigger>("inner_srv",
          std::bind(&TwoSrvs::inner_cb, this, std::placeholders::_1, std::placeholders::_2),
          ::rmw_qos_profile_default,
          callback_group_);

      client_ = this->create_client<std_srvs::srv::Trigger>("inner_srv");
  }

  void outer_cb(std_srvs::srv::Trigger::Request::SharedPtr, std_srvs::srv::Trigger::Response::SharedPtr res)
  {
    using namespace std::chrono_literals;

    RCLCPP_INFO(get_logger(), "outer srv callback");

    auto req = std::make_shared<std_srvs::srv::Trigger::Request>();
    auto future = client_->async_send_request(req);

    RCLCPP_INFO(get_logger(), "outer srv called inner srv");

    auto status = future.wait_for(3s);  //not spinning here!
    if (status == std::future_status::ready)
    {
      RCLCPP_INFO(get_logger(), "inner srv response is %s", future.get()->message.c_str());
      res->success = true;
      res->message = "good";
    }
    else
    {
      RCLCPP_ERROR(get_logger(), "inner srv future wait failed");
      res->success = false;
      res->message = "bad";
    }
  }

  void inner_cb(std_srvs::srv::Trigger::Request::SharedPtr, std_srvs::srv::Trigger::Response::SharedPtr res)
  {
    RCLCPP_INFO(get_logger(), "inner srv callback");
    res->success = true;
    res->message = "good";
  }

  rclcpp::callback_group::CallbackGroup::SharedPtr callback_group_;
  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr outer_srv_;
  rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr inner_srv_;
  rclcpp::Client<std_srvs::srv::Trigger>::SharedPtr client_;
};

int main(int argc, char* argv[])
{
  rclcpp::init(argc, argv);

  auto node = std::make_shared<TwoSrvs>();

  rclcpp::executors::MultiThreadedExecutor exec;
  exec.add_node(node);
  exec.spin();
}
edit flag offensive delete link more

Comments

I tried your code and also modified my code in this way. 25-90% of the service calls from a node or the command line tool are bad.
I'm using dashing, does this change anyting? How is it in eloquent or foxy?

MrCheesecake gravatar image MrCheesecake  ( 2020-07-16 08:44:40 -0500 )edit

I also did tests on eloquent and foxy now, but the results have been more bad.
But I found a fix which works for me. The fix is to also use MultiThreadedExecutor and add the client calling the service to a CallbackGroup. Adding the called service to a CallbackGroup if it don't call another is not needed I believe.
But thank you @jdlangs for pointing into the right direction for me.

MrCheesecake gravatar image MrCheesecake  ( 2020-07-16 11:48:27 -0500 )edit

Hi, I'm trying to apply this solution to my code, but I'm having some troubles. It seems all to work fine but after calling future.wait_for(3s) my node dies with the error: std::future_error: Broken promise. Any idea of how to solve it? Thanks!

albert.arla gravatar image albert.arla  ( 2022-06-15 08:47:43 -0500 )edit
3

answered 2020-06-10 08:22:08 -0500

vissermatthijs gravatar image

This my solutions at moment. Most important part is this:

        future = self.cli.call_async(self.req)

        while not future.done():
            time.sleep(0.5)
            print("Waiting...")

Full code:

class CheckZividCalibration(Node):
    """
    Class that checks the Zivid calibration
    """

    def __init__(self):
        super().__init__("check_zivid_calibration")

        # this group allows for callbacks to
        self.group = ReentrantCallbackGroup()

        # Create client for getting frames from the Zivid
        self.cli = self.create_client(zci.Capture3d, 'zivid_camera/capture', callback_group=self.group)
        # Service for checking the calibration
        self.srv = self.create_service(gci.CheckZividCalibrationRequest, 'check_zivid_calibration', self.check_zivid_calibration, callback_group=self.group)

        # wait for service
        self.req = zci.Capture3d.Request()
        while not self.cli.wait_for_service(1.0):
            self.get_logger().info("zivid service not available, waiting again...")

    def check_zivid_calibration(self, request: gci.CheckZividCalibrationRequest.Request, response: gci.CheckZividCalibrationRequest.Response):
        """
        Checks if the camera is still calibrated properly
        :return:
        """

        self.get_logger().info("Getting frame...")

        future = self.cli.call_async(self.req)

        while not future.done():
            time.sleep(0.5)
            print("Waiting...")

        # print(future.result())

        result = future.result()
        point_cloud = pointcloud2_to_array(result.cloud)
        point_cloud = split_rgb_field(point_cloud)
        corners = get_checkerboard_coords_from_zivid_frame(point_cloud)

        self.get_logger().info("got the frame!")
        response.success = True
        response.message = "Camera still calibrated properly"
        return response


def main(args=None):
    rclpy.init(args=args)

    executor = MultiThreadedExecutor(num_threads=8)

    check_zivid_calibration = CheckZividCalibration()

    executor.add_node(check_zivid_calibration)

    executor.spin()

    executor.shutdown()

    check_zivid_calibration.destroy_node()

    rclpy.shutdown()
edit flag offensive delete link more

Comments

Unfortunately I'm using C++.
But i assume, that the trick is to use MultiThreadedExecutor and CallbackGroups right?
Otherwise it will block when calling future.get() (future.done() in python).

MrCheesecake gravatar image MrCheesecake  ( 2020-06-10 08:40:32 -0500 )edit
1

answered 2020-11-26 13:38:52 -0500

Hi,

I recently came across this issue. In ROS 1, services are clearly different from action as they are synchronous. Porting code from ROS 1 to 2 usually requires service calls to keep synchronous, or induces a change in the architecture.

Here is a simple wrapper to handle this:

template <class ServiceT>
class ServiceNodeSync
{
    typedef typename ServiceT::Request RequestT;
    typedef typename ServiceT::Response ResponseT;
public:
    ServiceNodeSync(std::string name): node(std::make_shared<rclcpp::Node>(name))
    {    }

    void init(std::string service)
    {
    client = node->create_client<ServiceT>(service);
    client->wait_for_service();
    }

    ResponseT sendRequest(const RequestT &req)
    {
    return sendRequest(std::make_shared<RequestT>(req));
    }

    ResponseT sendRequest(const std::shared_ptr<RequestT> &req_ptr)
    {
    auto result = client->async_send_request(req_ptr);
    rclcpp::spin_until_future_complete(node, result);
    return *result.get();
    }

protected:
    rclcpp::Node::SharedPtr node;
    typename rclcpp::Client<ServiceT>::SharedPtr client;
};

It can be used as a member variable (say service_node_sync) of your base node Then the synchronous service call boils down to:

auto response = service_node_sync.sendRequest(request);

I guess this can be adapted for particular uses, but for now that is basically how I can teach/introduce ROS 2 services as being more or less the same as in ROS 1.

edit flag offensive delete link more

Comments

Thanks for posting, can you please provide a more complete example re. how to use this?

scott.nortman@gmail.com gravatar image scott.nortman@gmail.com  ( 2021-03-20 22:53:32 -0500 )edit

Question Tools

6 followers

Stats

Asked: 2020-02-04 15:43:38 -0500

Seen: 8,824 times

Last updated: Nov 26 '20