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 &req,std_srvs::Empty::Request &res)
00010 {
00011
00012 return true;
00013 }
00014
00015 static const char SERVICE1[] = "service1";
00016
00017 void call(ros::ServiceClient &client)
00018 {
00019
00020 if (client && client.exists() && client.isValid())
00021 {
00022
00023 std_srvs::Empty srv;
00024 client.call(srv);
00025 }
00026
00027
00028 }
00029
00030
00031 TEST(roscpp, ServiceDeadlocking)
00032 {
00033 ros::ServiceClient client;
00034 ros::AsyncSpinner spinner(1);
00035 spinner.start();
00036
00037 unsigned j=0;
00038 ros::Time start_time = ros::Time::now();
00039 unsigned seconds = 30;
00040 ros::Time stop_time = start_time + ros::Duration(seconds, 0);
00041
00042 while (true)
00043 {
00044 if ((j % 100 == 0) && (ros::Time::now() > stop_time))
00045 break;
00046
00047 {
00048 ros::NodeHandle n2;
00049 ros::ServiceServer service = n2.advertiseService(SERVICE1, dummyService);
00050 client = n2.serviceClient<std_srvs::Empty>(SERVICE1, true);
00051 call(client);
00052 service.shutdown();
00053 }
00054 ros::NodeHandle n;
00055 ros::ServiceServer service = n.advertiseService(SERVICE1, dummyService);
00056
00057 call(client);
00058 ++j;
00059 }
00060 ROS_INFO("Made it through %u loops in %u seconds", j, seconds);
00061 ASSERT_GE(j, 1000);
00062
00063 }
00064
00065 int main(int argc, char **argv)
00066 {
00067 testing::InitGoogleTest(&argc, argv);
00068 ros::init(argc, argv, "service_deadlock");
00069 return RUN_ALL_TESTS();
00070 }