Go to the documentation of this file.00001 #include <cstdlib>
00002 #include <gtest/gtest.h>
00003
00004 #include "ros/ros.h"
00005 #include "std_srvs/Empty.h"
00006 #include <ros/console.h>
00007 #include <ros/poll_manager.h>
00008
00009 bool dummyService(std_srvs::Empty::Request &, std_srvs::Empty::Request &)
00010 {
00011 return true;
00012 }
00013
00014 static const char SERVICE1[] = "service1";
00015
00016 void call(ros::ServiceClient &client)
00017 {
00018 if (client && client.exists() && client.isValid())
00019 {
00020 ROS_INFO("Calling service");
00021 std_srvs::Empty srv;
00022
00023 if (client.call(srv))
00024 ROS_INFO(" Successful call");
00025 else
00026 ROS_INFO(" Failed to call");
00027 }
00028 else
00029 ROS_INFO("Persistent client is invalid");
00030 }
00031
00032
00033 TEST(roscpp, ServiceDeadlocking)
00034 {
00035 ros::ServiceClient client;
00036 ros::AsyncSpinner spinner(3);
00037 spinner.start();
00038
00039 unsigned j = 0;
00040 ros::Time start_time = ros::Time::now();
00041 unsigned seconds = 30;
00042 ros::Time stop_time = start_time + ros::Duration(seconds, 0);
00043
00044 while (true)
00045 {
00046 if ((j % 500 == 0) && (ros::Time::now() > stop_time))
00047 break;
00048
00049 {
00050 ros::NodeHandle n2;
00051 ros::ServiceServer service = n2.advertiseService(SERVICE1, dummyService);
00052 client = n2.serviceClient<std_srvs::Empty>(SERVICE1, true);
00053 call(client);
00054 service.shutdown();
00055 }
00056 ros::NodeHandle n;
00057 ros::ServiceServer service = n.advertiseService(SERVICE1, dummyService);
00058
00059 call(client);
00060 ++j;
00061 }
00062 ROS_INFO("Made it through %u loops in %u seconds", j, seconds);
00063 ASSERT_GE(j, 1000);
00064 }
00065
00066 int main(int argc, char **argv)
00067 {
00068 testing::InitGoogleTest(&argc, argv);
00069 ros::init(argc, argv, "service_deadlock");
00070 return RUN_ALL_TESTS();
00071 }