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

ros service dead lock?

asked 2016-08-28 08:50:12 -0500

Winston gravatar image

updated 2016-08-28 08:57:17 -0500

This is the situation:
Node A has a service client which calls a service server defined in node B for all the time.

In the meanwhile, node B also has a service client which calls a service server defined in node A for all the time.

In other words, there are a service client and server in node A, and there are also a service server and client in node B. And they call each other all the time.

Now comes the problem, the program hangs there and no call is successful. It seems there is a deadlock. Any one could give me a detailed explanation? And any one could provide me with a solution? Thanks!

Node A:

#include "ros/ros.h"
#include "roscpp_tutorials/TwoInts.h"
#include <cstdlib>

bool test(roscpp_tutorials::TwoInts::Request  &req,
         roscpp_tutorials::TwoInts::Response &res )
{
  res.sum = req.a + req.b;
  ROS_INFO("test : x=%ld, y=%ld", (long int)req.a, (long int)req.b);
  ROS_INFO(" test sending back response: [%ld]", (long int)res.sum);
  return true;
}

int main(int argc, char **argv)
{
    ros::init(argc, argv, "add_two_ints_client");
    ros::NodeHandle n;

    ros::ServiceClient client = n.serviceClient<roscpp_tutorials::TwoInts>("add_two_ints");
    ros::ServiceServer server = n.advertiseService("test", test);

    ros::Rate rate(10);

    roscpp_tutorials::TwoInts srv;
    srv.request.a = 1;
    srv.request.b = 2;

    while(ros::ok())
    {
        if (client.call(srv))
        {
          ROS_INFO("Sum: %ld", (long int)srv.response.sum);
        }
        else
        {
          ROS_ERROR("Failed to call service add_two_ints");
        }
        ros::spinOnce();
        rate.sleep();
    }

    return 0;
}

Node B:

#include "ros/ros.h"
#include "roscpp_tutorials/TwoInts.h"

bool add(roscpp_tutorials::TwoInts::Request  &req,
         roscpp_tutorials::TwoInts::Response &res )
{
  res.sum = req.a + req.b;
  ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
  ROS_INFO("  sending back response: [%ld]", (long int)res.sum);
  return true;
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "add_two_ints_server");
  ros::NodeHandle n;

  ros::ServiceServer service = n.advertiseService("add_two_ints", add);
  ros::ServiceClient client = n.serviceClient<roscpp_tutorials::TwoInts>("test");

  ros::Rate rate(10);

  roscpp_tutorials::TwoInts srv;
  srv.request.a = 1;
  srv.request.b = 2;

  while(ros::ok())
  {
      if (client.call(srv))
      {
        ROS_INFO("test: %ld", (long int)srv.response.sum);
      }
      else
      {
        ROS_ERROR("Failed to call service test");
      }
      ros::spinOnce();
      rate.sleep();
  }
  //ros::spin();

  return 0;
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-08-28 12:47:00 -0500

ahendrix gravatar image

Yep, definitely looks like you've created a deadlock.

By default, roscpp runs in a single thread and processes your service callbacks as part of ros::spinOnce() (or ros::spin()). Since service calls are blocking, when each program starts the service call it can't execute callbacks until the service call completes.

Both of your programs are probably sitting at client.call(), waiting for the other program to process its service callback.

There are a couple of ways to solve this:

  • Re-design your program so that it doesn't have a deadlock. (I would start by asking whether you really need blocking service calls; can you use topics instead?)
  • Use an AyncSpinner or some other mechanism to process callbacks in a different thread
edit flag offensive delete link more

Comments

I want to guarantee that the client's EVERY message/call would be received by the server but it seems that topics could not guarantee that. I won't use ros service if topics could meet my requirement. @ahendrix

Winston gravatar image Winston  ( 2016-08-29 01:31:18 -0500 )edit

If you really need to guarantee delivery of EVERY message, then services may be the only answer. However, most of the users I find who say this don't actually need it; a slight change to the message semantics might be tolerant to dropped messages.

ahendrix gravatar image ahendrix  ( 2016-08-29 10:55:02 -0500 )edit

Thank you! I would like to how how to change the message's semantics to be tolerant to dropped messages. Could you give me some advice?

Winston gravatar image Winston  ( 2016-08-31 20:04:49 -0500 )edit
1

I have no idea. They're your messages and your requirement for no dropped messages. If you want advice about specific messages and a specific application, I suggest you open a new question that describes your application and your messages and asks how to make it more tolerant to dropped messages.

ahendrix gravatar image ahendrix  ( 2016-08-31 21:22:15 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2016-08-28 08:50:12 -0500

Seen: 2,641 times

Last updated: Aug 28 '16