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

Client doesn't return when you create a client class ROS2

asked 2021-04-19 09:13:37 -0500

Kappa95 gravatar image

Hi community, I would like to write a client and server node using classes. I started writing the client in a class "form" using the tutorial in the documentation and I used the same messages and the same identical code for the server node. I wanted to create a client class which is querying each 500ms the same msg to the server. Searching on the ROS Answer I found a similar question. And using a solution like that I got that the client now is stuck in a deadlock or similar because send the first request but later no and the code continue to run.

The client that I had written is this:

#include "rclcpp/rclcpp.hpp"
#include "example_interfaces/srv/add_two_ints.hpp"

#include <chrono>
#include <cstdlib>
#include <memory>
#include <functional>

using namespace std::chrono_literals;


class client_foo : public rclcpp::Node
{
    public:
    client_foo(const std::string &node_name) : rclcpp::Node(node_name)
    {
        client_ = this->create_client<example_interfaces::srv::AddTwoInts>("servizio", rmw_qos_profile_services_default);
        cb_grp_client_ = this->create_callback_group(rclcpp::callback_group::CallbackGroupType::MutuallyExclusive);

        while (!client_->wait_for_service(1s))
        {
            if (!rclcpp::ok())
            {
                RCLCPP_ERROR(get_logger(), "Errore mentre aspetto");
                exit(1);
            }
            RCLCPP_INFO(get_logger(), "Servizio non disponibile aspetta...");
        }

        timer_cb_ = create_wall_timer(500ms, std::bind(&client_foo::start, this));
    }

    private:
        rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedPtr client_;
        rclcpp::callback_group::CallbackGroup::SharedPtr cb_grp_client_;
        // Timer per il callback
        rclcpp::TimerBase::SharedPtr timer_cb_;

        example_interfaces::srv::AddTwoInts::Response::SharedPtr start()
        {
            auto request = std::make_shared<example_interfaces::srv::AddTwoInts::Request>();
            request->a = 1;
            request->b = 2;

            auto result = client_->async_send_request(request);
            result.wait();

            RCLCPP_INFO(get_logger(), "Results!");
            return result.get();
        }
};


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

    std::shared_ptr<client_foo> client_node =
        std::make_shared<client_foo>("client_foo");

    exe.add_node(client_node);
    exe.spin();
    return 0;
}

Probably the question is very silly but I don't get the point where the code fails. Someone can help me?

Thank you so much.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-04-19 11:21:24 -0500

sgvandijk gravatar image

I think you're on the right path, but two points:

  1. The callback group that you created is MutuallyExclusive, which means that callbacks from the same node cannot be run in parallel. This means that while your start callback from the timer is still running, no other callback on the same node can be started, like the service callback--you don't specify a callback but under the hood there is still a callback that is queued for when the result arrives. Because you .wait() on the result in the timer callback, the service is blocked, the result doesn't actually arrive, and .wait() never returns, i.e. you've got a deadlock. Instead, you need to create a Reentrant callback group, which does allow callbacks on the the same node to run in parallel:

    cb_grp_client_ = this->create_callback_group(rclcpp::callback_group::CallbackGroupType::Reentrant);
    

    That, or you create two separate groups.

  2. You aren't actually using the callback group. You have to pass it when you create the client:

    this->create_client<example_interfaces::srv::AddTwoInts>("servizio", rmw_qos_profile_services_default, cb_grp_client_)
    

    and when you create the timer:

    create_wall_timer(500ms, std::bind(&client_foo::start, this), cb_grp_client_);
    

    Otherwise both use the default group which is again MutuallyExclusive.

edit flag offensive delete link more

Comments

Thank you so much! The answer is very clear! So it means that each time I'm creating a service or a client I am using a thread; and in this case I was using 2 threads: one for the client and one for the start callback. In this case having the group with the mutual exclusion, one thread was waiting the end of the other, but they were stuck. Do I understand right?

Kappa95 gravatar image Kappa95  ( 2021-04-19 15:05:03 -0500 )edit

Well, actually by default as many threads as you have cores are created, and they just pick up work to do whenever they are ready, where work can be running a callback function or sending a service request etc. You can't predict which thread handles which bit of work. Because normally you probably don't want multiple bits of code in the same node to run at the same time, to prevent race conditions and such, the default callback group ensures that that doesn't happen and that the callbacks are 'mutually exclusive', even if they happen to be picked up by different threads.

So on the flipside, by using a reentrant group (or multiple mutual exclusive ones in the same node) you possibly open yourself up to this kind of dangers. That is why it is good practice to use proper async calls where possible and then be ...(more)

sgvandijk gravatar image sgvandijk  ( 2021-04-20 11:35:50 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-04-19 09:13:37 -0500

Seen: 832 times

Last updated: Apr 19 '21