service_deadlock.cpp
Go to the documentation of this file.
1 #include <cstdlib>
2 #include <gtest/gtest.h>
3 
4 #include "ros/ros.h"
5 #include "std_srvs/Empty.h"
6 #include <ros/console.h>
7 #include <ros/poll_manager.h>
8 
9 bool dummyService(std_srvs::Empty::Request &, std_srvs::Empty::Request &)
10 {
11  return true;
12 }
13 
14 static const char SERVICE1[] = "service1";
15 
16 void call(ros::ServiceClient &client)
17 {
18  if (client && client.exists() && client.isValid())
19  {
20  ROS_INFO("Calling service");
21  std_srvs::Empty srv;
22  // these will alternate successful and failed.
23  if (client.call(srv))
24  ROS_INFO(" Successful call");
25  else
26  ROS_INFO(" Failed to call");
27  }
28  else
29  ROS_INFO("Persistent client is invalid");
30 }
31 
32 // this only verifies that it doesn't deadlock. Should run about 60 seconds.
33 TEST(roscpp, ServiceDeadlocking)
34 {
35  ros::ServiceClient client;
36  ros::AsyncSpinner spinner(3);
37  spinner.start();
38 
39  unsigned j = 0;
40  ros::Time start_time = ros::Time::now();
41  unsigned seconds = 30;
42  ros::Time stop_time = start_time + ros::Duration(seconds, 0);
43 
44  while (true)
45  {
46  if ((j % 500 == 0) && (ros::Time::now() > stop_time))
47  break;
48 
49  {
50  ros::NodeHandle n2;
52  client = n2.serviceClient<std_srvs::Empty>(SERVICE1, true);
53  call(client);
54  service.shutdown();
55  }
58 
59  call(client);
60  ++j;
61  }
62  ROS_INFO("Made it through %u loops in %u seconds", j, seconds);
63  ASSERT_GE(j, 1000);
64 }
65 
66 int main(int argc, char **argv)
67 {
68  testing::InitGoogleTest(&argc, argv);
69  ros::init(argc, argv, "service_deadlock");
70  return RUN_ALL_TESTS();
71 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
int main(int argc, char **argv)
TEST(roscpp, ServiceDeadlocking)
static const char SERVICE1[]
#define ROS_INFO(...)
bool dummyService(std_srvs::Empty::Request &, std_srvs::Empty::Request &)
bool isValid() const
void call(ros::ServiceClient &client)
static Time now()


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46