0
$\begingroup$

Rosanswers logo

Hello,

This question is actually related to : https://answers.ros.org/question/301872/ros2-service-spin_until_future_complete-blocking-when-calling-a-service-that-calls-another-service/

But I wrote a minimal example and wanted to have your feedback on how to fix this.

So I'm using ROS2 Bouncy, built from source on Ubuntu 18.04. I have a node that subscribe to a topic and in the callback function of the sub, I get stuck if I try to rclpy.spin_once(self).

I wrote a minimal package to show the problem, which can be found here : https://github.com/MarcTestier/test_repo/tree/ros2_spin_bug_test

I was actually trying to call a service from the callback function but got stuck when doing rclpy.spin_until_future_complete(node, future) to get the answer form the service.

So any idea how to call a service from the callback function of a subscriber ?? Maybe threads ??

Thanks.


Originally posted by Marc Testier on ROS Answers with karma: 203 on 2018-08-30

Post score: 5

$\endgroup$

3 Answers 3

0
$\begingroup$

Rosanswers logo

Here is the solution proposed by @codebot to call a service from the callback of a sub : https://github.com/codebot/ros2_patterns/blob/master/sub_calling_service.py

Here is what he said about the solution though :

The key issue is that calling a service synchronously from within a subscriber callback is usually not a good design, because it's possible that the inbound messages will be coming more quickly than the service can process them, which could result in an uncontrolled message queue forming. The general pattern is that topic callbacks should be "fast".

Anyway, if you still want to try :

To accomplish this in rclpy, we can asynchronously issue the service request. Then in the main spin() loop, we can look at the array of futures and, whenever one is completed, we can read its result.

So the way I threw that together will also result in an unbounded request queue if the inbound message stream is coming really fast and the service is slow but you could control that by looking at the length of self.client_futures and not adding to it if it's already larger than some threshold.

#!/usr/bin/env python3
import sys

import rclpy
from rclpy.node import Node
from std_msgs.msg import String
from test_msgs.srv import Empty

class SubscriberClientAsync(Node):

    def __init__(self):
        super().__init__('sub_client_node')
        self.client = self.create_client(Empty, 'service')
        self.sub = self.create_subscription(String, 'topic', self.topic_cb)
        self.client_futures = []

    def topic_cb(self, msg):
        print("sub_cb({})".format(msg.data))
        self.client_futures.append(self.client.call_async(Empty.Request()))

    def spin(self):
        while rclpy.ok():
            rclpy.spin_once(self)
            incomplete_futures = []
            for f in self.client_futures:
                if f.done():
                    res = f.result()
                    print("received service result: {}".format(res))
                else:
                    incomplete_futures.append(f)
            self.client_futures = incomplete_futures

if __name__ == '__main__':
    rclpy.init()
    node = SubscriberClientAsync()
node.spin()

Originally posted by Marc Testier with karma: 203 on 2018-08-30

This answer was ACCEPTED on the original site

Post score: 2


Original comments

Comment by lin404 on 2020-01-28:
@Marc Testier

The key issue is that calling a service synchronously from within a subscriber callback is usually not a good design

what should I do if I wanna call a service synchronously due to the msg from a subscriber callback? Can you give me an idea what I should look into?

Comment by aarsh_t on 2021-10-29:
just in case if link mentioned in msg above doesn't works, here is the new one. (https://github.com/codebot/ros2_patterns/blob/master/nested_services/sub_calling_service.py)

$\endgroup$
0
$\begingroup$

Rosanswers logo

The problem is, that you can't use the spin_node_until_future_complete() command inside the outer callback. The solution is to use an MultiThreadedExecutor and different callback groups. Then you can call the inner service by giving it a callback function (instead of waiting for the return code with spin_node_until_future_complete).

If you want to wait for the result from the inner service call before the outer service callback finishes you need to block the thread with a while(return_from_inner_service == false) loop. This is important if your outer callback is from a service, because then you want to receive the inner service result and use it to compute the result of the outer service. But this is bad design, because you block the spin() call from the outer service. Luckily we can still handle other callbacks with the MultiThreadedExecutor as long as we assign them to a different callback group. If the outer callback is from a topic you don't want to block the callback, just handle the inner service call inside the assigned callback function. It will execute asynchronous.

Here is some code example in C++ (assuming all necessary headers included and ROS services created)

Create the MultiThreadedExecuter and an instance of the Node in main:

int main(int argc, char *argv[])
{
    rclcpp::init(argc, argv);
    rclcpp::executors::MultiThreadedExecutor executor;
    auto node = std::make_shared<Communication>();
    executor.add_node(node);
    executor.spin();
    rclcpp::shutdown();
    return 0;
}

Create seperate Callback group and assign it to the inner service client (inside the Node/class constructor):

callback_group_input_ = this->create_callback_group(rclcpp::callback_group::CallbackGroupType::MutuallyExclusive);
get_input_client_ = this->create_client<petra_core::srv::GetInput>("GetInput", rmw_qos_profile_services_default, callback_group_input_);

Inside the outer callback from a topic or service, send the inner_request and define a callback for it:

int choice = -1;
    auto inner_client_callback = [&,this](rclcpp::Client<petra_core::srv::GetInput>::SharedFuture inner_future)
        { 
            auto result = inner_future.get();
            choice = stoi(result->input);
            RCLCPP_INFO(this->get_logger(), "[inner service] callback executed");
        };
    auto inner_future_result = get_input_client_->async_send_request(inner_request, inner_client_callback);

If it is necessary to wait inside the outer callback for the result block the thread:

// Wait for the result.
    while (choice < 0 && rclcpp::ok())
    {
        std::this_thread::sleep_for(std::chrono::milliseconds(10));
    }

I hope it helps you, or whoever has the same problem. I was stuck with this for weeks...


Originally posted by Andreas Z with karma: 171 on 2020-05-18

This answer was NOT ACCEPTED on the original site

Post score: 2

$\endgroup$
0
$\begingroup$

Rosanswers logo

I was stuck on this for whole day, so I'm adding my solution in case anyone else runs into a similar problem. The previously mentioned solutions are on the right track, but they are incomplete. There is an official solution in the ros docs, which I am pasting here just in case the link breaks.

Note that this problem is not unique to calling a service client from within a subscriber callback. This problem occurs whenever you have to call a callback from within a callback. Therefore the example of calling a service from within the timer callback is effectively the same as calling a service from within a subscription callback, or calling a service from within a service callback.

The solution is to put your nested callbacks in different callback groups (see the link above) and to use std::future::wait_for() instead of rclcpp::spin_until_future_complete().

#include <chrono>
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "std_srvs/srv/empty.hpp"

using namespace std::chrono_literals;

namespace cb_group_demo
{
class DemoNode : public rclcpp::Node
{
public:
    DemoNode() : Node("client_node")
    {
        client_cb_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
        timer_cb_group_ = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
        client_ptr_ = this->create_client<std_srvs::srv::Empty>("test_service", rmw_qos_profile_services_default,
                                                                client_cb_group_);
        timer_ptr_ = this->create_wall_timer(1s, std::bind(&DemoNode::timer_callback, this),
                                            timer_cb_group_);
    }

private:
    rclcpp::CallbackGroup::SharedPtr client_cb_group_;
    rclcpp::CallbackGroup::SharedPtr timer_cb_group_;
    rclcpp::Client<std_srvs::srv::Empty>::SharedPtr client_ptr_;
    rclcpp::TimerBase::SharedPtr timer_ptr_;

    void timer_callback()
    {
        RCLCPP_INFO(this->get_logger(), "Sending request");
        auto request = std::make_shared<std_srvs::srv::Empty::Request>();
        auto result_future = client_ptr_->async_send_request(request);

        // Do this instead of rclcpp::spin_until_future_complete()
        std::future_status status = result_future.wait_for(10s);  // timeout to guarantee a graceful finish
        if (status == std::future_status::ready) {
            RCLCPP_INFO(this->get_logger(), "Received response");
            std::shared_ptr<ServiceT::Response> response = result_future.get();
            // Do something with response 
        }
    }
};  // class DemoNode
}   // namespace cb_group_demo

int main(int argc, char* argv[])
{
    rclcpp::init(argc, argv);
    auto client_node = std::make_shared<cb_group_demo::DemoNode>();
    rclcpp::executors::MultiThreadedExecutor executor;
    executor.add_node(client_node);

    RCLCPP_INFO(client_node->get_logger(), "Starting client node, shut down with CTRL-C");
    executor.spin();
    RCLCPP_INFO(client_node->get_logger(), "Keyboard interrupt, shutting down.\n");

    rclcpp::shutdown();
    return 0;
}

Originally posted by ld_returned_1 with karma: 11 on 2023-04-13

This answer was NOT ACCEPTED on the original site

Post score: 1


Original comments

Comment by aserbremen on 2023-06-07:
Do you know how to perform or whether it is possible such a service call, when a node is configured as a component and loaded as a composable node?

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.