ed
test_service_speed.cpp
Go to the documentation of this file.
1 #include <ed_msgs/SetLabel.h>
2 #include <ed_msgs/SimpleQuery.h>
3 #include <ed_msgs/SetClick.h>
4 #include <ed_msgs/GetGUICommand.h>
5 #include <ed_msgs/GetMeasurements.h>
6 #include <ed_msgs/RaiseEvent.h>
7 
8 #include <ros/ros.h>
9 
10 #include <tue/profiling/timer.h>
11 
12 int main(int argc, char **argv) {
13  ros::init(argc, argv, "ed_test_service_speed");
14 
15  ros::NodeHandle nh;
16 
17  int N = 1;
18 
19  {
20  ros::ServiceClient client = nh.serviceClient<ed_msgs::SimpleQuery>("/ed/simple_query");
21  client.waitForExistence();
22  ed_msgs::SimpleQuery srv;
23 
24  tue::Timer t;
25  t.start();
26 
27  for(int i = 0; i < N; ++i)
28  {
29 
30  if (!client.call(srv))
31  {
32  std::cout << client.getService() << " : could not be called" << std::endl;
33  }
34  }
35 
36  std::cout << client.getService() << ": " << t.getElapsedTimeInMilliSec() / N << " ms" << std::endl;
37  }
38 
39  {
40  ros::ServiceClient client = nh.serviceClient<ed_msgs::SetLabel>("/ed/gui/set_label");
41  client.waitForExistence();
42  ed_msgs::SetLabel srv;
43 
44  tue::Timer t;
45  t.start();
46 
47  for(int i = 0; i < N; ++i)
48  {
49 
50  if (!client.call(srv))
51  {
52  std::cout << client.getService() << " : could not be called" << std::endl;
53  }
54  }
55 
56  std::cout << client.getService() << ": " << t.getElapsedTimeInMilliSec() / N << " ms" << std::endl;
57  }
58 
59  {
60  ros::ServiceClient client = nh.serviceClient<ed_msgs::GetMeasurements>("/ed/gui/get_measurements");
61  client.waitForExistence();
62  ed_msgs::GetMeasurements srv;
63 
64  tue::Timer t;
65  t.start();
66 
67  for(int i = 0; i < N; ++i)
68  {
69 
70  if (!client.call(srv))
71  {
72  std::cout << client.getService() << " : could not be called" << std::endl;
73  }
74  }
75 
76  std::cout << client.getService() << ": " << t.getElapsedTimeInMilliSec() / N << " ms" << std::endl;
77  }
78 
79  {
80  ros::ServiceClient client = nh.serviceClient<ed_msgs::GetGUICommand>("/ed/gui/get_gui_command");
81  client.waitForExistence();
82  ed_msgs::GetGUICommand srv;
83 
84  tue::Timer t;
85  t.start();
86 
87  for(int i = 0; i < N; ++i)
88  {
89 
90  if (!client.call(srv))
91  {
92  std::cout << client.getService() << " : could not be called" << std::endl;
93  }
94  }
95 
96  std::cout << client.getService() << ": " << t.getElapsedTimeInMilliSec() / N << " ms" << std::endl;
97  }
98 
99  {
100  ros::ServiceClient client = nh.serviceClient<ed_msgs::RaiseEvent>("/ed/gui/raise_event");
101  client.waitForExistence();
102  ed_msgs::RaiseEvent srv;
103 
104  tue::Timer t;
105  t.start();
106 
107  for(int i = 0; i < N; ++i)
108  {
109 
110  if (!client.call(srv))
111  {
112  std::cout << client.getService() << " : could not be called" << std::endl;
113  }
114  }
115 
116  std::cout << client.getService() << ": " << t.getElapsedTimeInMilliSec() / N << " ms" << std::endl;
117  }
118 
119  return 0;
120 }
t
Timer t
std::cout
Timer::start
void start()
client
ros::ServiceClient client
Definition: show_gui.cpp:6
timer.h
tue::Timer
Timer::getElapsedTimeInMilliSec
double getElapsedTimeInMilliSec() const
std::endl
T endl(T... args)
main
int main(int argc, char **argv)
Definition: test_service_speed.cpp:12