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

ServiceServer on Arduino -- Service requests will eventually hang

asked 2013-09-09 09:45:57 -0500

River gravatar image

Hello,

I have encountered an issue with rosserial wherein if I run a ServiceServer on my arduino -- after a variable number of requests to the service, the request will indefinitely hang. I have created a simplified example to re-create the problem (I added a Publisher as it seems to decrease the number of requests before failure):

Arduino code:

#include <ros.h>
#include <ArduinoHardware.h>
#include <std_msgs/UInt16.h>
#include <std_srvs/Empty.h>

ros::NodeHandle  nh;
using std_srvs::Empty;

// Create a publisher that generates a random die roll
std_msgs::UInt16 die;
ros::Publisher die_pub("random_die_roll", &die);

// Create a service server that takes nothing and returns nothing
void callback(const Empty::Request & req, Empty::Response & res)
{
  // Simulate function running for a non-deterministic amount of time
  delay(random(5,70));
}

ros::ServiceServer<Empty::Request, Empty::Response> server("get_nothing",&callback);

void setup()
{
  // Startup ROS
  nh.initNode();
  nh.advertiseService(server);
  nh.advertise(die_pub);
}

void loop()
{
  // Publish die roll
  die.data = random(1, 7);
  die_pub.publish(&die);
  nh.spinOnce();
  delay(75);
}

Python node code:

#!/usr/bin/env python
import roslib; roslib.load_manifest('test_arduino')
import rospy
from std_srvs.srv import Empty

def main():
    rospy.init_node("test_problem")
    rospy.wait_for_service('get_nothing')
    get_nothing_service = rospy.ServiceProxy('get_nothing', Empty)
    count = 0
    while not rospy.is_shutdown():
        get_nothing_service()
        print "Got nothing...", count
        count += 1
        rospy.sleep(0.5)

if __name__ == "__main__":
    main()

Environment:

  • Ubuntu 12.04
  • ROS Groovy
  • rosserial (4d34f24181b9570ac1f5a2be9ffbdbf4e8a3d59a)
  • Seeeduino Mega w/ ATmega 1280

Any help is appreciated. I have a feeling it's just a mistake in my understanding.

Thanks.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2013-09-26 09:13:30 -0500

River gravatar image

For someone in the future who may run into this problem, I got around it by creating a "psuedo-service". I used two publishers. The requester would publish a request and the server would publish a result after it heard the request. It worked very well, but it's not a "real" answer in my opinion.

edit flag offensive delete link more
1

answered 2017-09-09 22:24:17 -0500

TomOConnell gravatar image

Under some circumstances, I believe this can be related to pull request #308, where if the client exceeds one of the timeouts in nh.spinOnce(), the flag indicating it is configured will be set false, and the check before publishing will fail. The rosserial_python node currently goes in to an infinite loop until it receives a response from the correct service server.

I worked around this by making the code that sets the configuration flag false upon timeout optional at compile time, but I don't think this is the most clean solution in general.

See my fork. It may have changed, but commits around the time of this answer should have the change.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2013-09-09 09:45:57 -0500

Seen: 3,530 times

Last updated: Sep 09 '13