cm_test.cpp
Go to the documentation of this file.
1 // Copyright (C) 2012, hiDOF INC.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of hiDOF Inc nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
30 
31 #include <ros/ros.h>
32 #include <gtest/gtest.h>
33 
34 #include <controller_manager_msgs/ListControllers.h>
35 #include <controller_manager_msgs/ListControllerTypes.h>
36 #include <controller_manager_msgs/LoadController.h>
37 #include <controller_manager_msgs/SwitchController.h>
38 #include <controller_manager_msgs/UnloadController.h>
39 
40 
41 using namespace controller_manager_msgs;
42 
43 TEST(CMTests, loadUnloadOk)
44 {
45  ros::NodeHandle nh;
46  ros::ServiceClient load_client = nh.serviceClient<LoadController>("/controller_manager/load_controller");
47  ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
48 
49  // Load single-interface controller
50  {
51  LoadController srv;
52  srv.request.name = "my_controller";
53  bool call_success = load_client.call(srv);
54  ASSERT_TRUE(call_success);
55  EXPECT_TRUE(srv.response.ok);
56  }
57 
58  // Load multi-interface controller:
59  // Two required interfaces
60  {
61  LoadController srv;
62  srv.request.name = "vel_eff_controller";
63  bool call_success = load_client.call(srv);
64  ASSERT_TRUE(call_success);
65  EXPECT_TRUE(srv.response.ok);
66  }
67 
68  // Load multi-interface controller:
69  // One required (and existing) interface and one optional (and non-existent) interface
70  {
71  LoadController srv;
72  srv.request.name = "optional_interfaces_controller";
73  bool call_success = load_client.call(srv);
74  ASSERT_TRUE(call_success);
75  EXPECT_TRUE(srv.response.ok);
76  }
77 
78  // Unload single-interface controller
79  {
80  UnloadController srv;
81  srv.request.name = "my_controller";
82  bool call_success = unload_client.call(srv);
83  ASSERT_TRUE(call_success);
84  EXPECT_TRUE(srv.response.ok);
85  }
86 
87  // Unload multi-interface controllers
88  {
89  UnloadController srv;
90  srv.request.name = "vel_eff_controller";
91  bool call_success = unload_client.call(srv);
92  ASSERT_TRUE(call_success);
93  EXPECT_TRUE(srv.response.ok);
94  }
95  {
96  UnloadController srv;
97  srv.request.name = "optional_interfaces_controller";
98  bool call_success = unload_client.call(srv);
99  ASSERT_TRUE(call_success);
100  EXPECT_TRUE(srv.response.ok);
101  }
102 }
103 
104 TEST(CMTests, loadUnloadKo)
105 {
106  ros::NodeHandle nh;
107  ros::ServiceClient load_client = nh.serviceClient<LoadController>("/controller_manager/load_controller");
108  ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
109 
110  // Load non-existent controller
111  {
112  LoadController srv;
113  srv.request.name = "nonexistent_controller";
114  bool call_success = load_client.call(srv);
115  ASSERT_TRUE(call_success);
116  EXPECT_FALSE(srv.response.ok);
117  }
118 
119  // Load controller requesting non-existient HW interface
120  {
121  LoadController srv;
122  srv.request.name = "non_existent_interface_controller";
123  bool call_success = load_client.call(srv);
124  ASSERT_TRUE(call_success);
125  EXPECT_FALSE(srv.response.ok);
126  }
127 
128  // Load controller requesting non-existent resource from valid HW interface
129  {
130  LoadController srv;
131  srv.request.name = "non_existent_resource_controller";
132  bool call_success = load_client.call(srv);
133  ASSERT_TRUE(call_success);
134  EXPECT_FALSE(srv.response.ok);
135  }
136 
137  // Load multi-interface controller:
138  // Two required HW interfaces, of which one is non-existent
139  {
140  LoadController srv;
141  srv.request.name = "non_existing_multi_interface_controller";
142  bool call_success = load_client.call(srv);
143  ASSERT_TRUE(call_success);
144  EXPECT_FALSE(srv.response.ok);
145  }
146 
147  // Unload not loaded controller
148  {
149  UnloadController srv;
150  srv.request.name = "my_controller";
151  bool call_success = unload_client.call(srv);
152  ASSERT_TRUE(call_success);
153  EXPECT_FALSE(srv.response.ok);
154  }
155 }
156 
157 TEST(CMTests, switchController)
158 {
159  ros::NodeHandle nh;
160  ros::ServiceClient load_client = nh.serviceClient<LoadController>("/controller_manager/load_controller");
161  ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
162  ros::ServiceClient switch_client = nh.serviceClient<SwitchController>("/controller_manager/switch_controller");
163 
164  // Load controllers
165  {
166  LoadController srv;
167  srv.request.name = "my_controller";
168  load_client.call(srv);
169  srv.request.name = "my_controller2";
170  load_client.call(srv);
171  srv.request.name = "vel_eff_controller";
172  load_client.call(srv);
173  }
174 
175  // Successful STRICT start
176  {
177  SwitchController srv;
178  srv.request.start_controllers.push_back("my_controller");
179  srv.request.strictness = srv.request.STRICT;
180  bool call_success = switch_client.call(srv);
181  ASSERT_TRUE(call_success);
182  EXPECT_TRUE(srv.response.ok);
183  }
184 
185  // Successful STRICT stop
186  {
187  SwitchController srv;
188  srv.request.stop_controllers.push_back("my_controller");
189  srv.request.strictness = srv.request.STRICT;
190  bool call_success = switch_client.call(srv);
191  ASSERT_TRUE(call_success);
192  EXPECT_TRUE(srv.response.ok);
193  }
194 
195  // Successful STRICT start
196  {
197  SwitchController srv;
198  srv.request.start_controllers.push_back("vel_eff_controller");
199  srv.request.strictness = srv.request.STRICT;
200  bool call_success = switch_client.call(srv);
201  ASSERT_TRUE(call_success);
202  EXPECT_TRUE(srv.response.ok);
203  }
204 
205  // Successful STRICT stop+start
206  {
207  SwitchController srv;
208  srv.request.start_controllers.push_back("my_controller");
209  srv.request.stop_controllers.push_back("vel_eff_controller");
210  srv.request.strictness = srv.request.STRICT;
211  bool call_success = switch_client.call(srv);
212  ASSERT_TRUE(call_success);
213  EXPECT_TRUE(srv.response.ok);
214  }
215 
216  // Back to no running controllers
217  {
218  SwitchController srv;
219  srv.request.stop_controllers.push_back("my_controller");
220  srv.request.strictness = srv.request.STRICT;
221  bool call_success = switch_client.call(srv);
222  ASSERT_TRUE(call_success);
223  EXPECT_TRUE(srv.response.ok);
224  }
225  // Unsuccessful STRICT start
226  {
227  SwitchController srv;
228  srv.request.start_controllers.push_back("non_existent_controller");
229  srv.request.strictness = srv.request.STRICT;
230  bool call_success = switch_client.call(srv);
231  ASSERT_TRUE(call_success);
232  EXPECT_FALSE(srv.response.ok);
233  }
234 
235  // Unsuccessful STRICT stop
236  {
237  SwitchController srv;
238  srv.request.stop_controllers.push_back("non_existent_controller");
239  srv.request.strictness = srv.request.STRICT;
240  bool call_success = switch_client.call(srv);
241  ASSERT_TRUE(call_success);
242  EXPECT_FALSE(srv.response.ok);
243  }
244 
245  // Unsuccessful STRICT switch: invalid stop
246  {
247  SwitchController srv;
248  srv.request.start_controllers.push_back("my_controller");
249  srv.request.stop_controllers.push_back("non_existent_controller");
250  srv.request.strictness = srv.request.STRICT;
251  bool call_success = switch_client.call(srv);
252  ASSERT_TRUE(call_success);
253  EXPECT_FALSE(srv.response.ok);
254  }
255 
256  // Unsuccessful STRICT switch: invalid start
257  {
258  SwitchController srv;
259  srv.request.start_controllers.push_back("non_existent_controller");
260  srv.request.stop_controllers.push_back("my_controller");
261  srv.request.strictness = srv.request.STRICT;
262  bool call_success = switch_client.call(srv);
263  ASSERT_TRUE(call_success);
264  EXPECT_FALSE(srv.response.ok);
265  }
266 
267  // Unsuccessful STRICT start: Resource conflict within single controller
268  {
269  SwitchController srv;
270  srv.request.start_controllers.push_back("self_conflict_controller");
271  srv.request.strictness = srv.request.STRICT;
272  bool call_success = switch_client.call(srv);
273  ASSERT_TRUE(call_success);
274  EXPECT_FALSE(srv.response.ok);
275  }
276 
277  // Unsuccessful STRICT start: Resource conflict between two controllers
278  {
279  SwitchController srv;
280  srv.request.start_controllers.push_back("my_controller");
281  srv.request.start_controllers.push_back("my_controller2");
282  srv.request.strictness = srv.request.STRICT;
283  bool call_success = switch_client.call(srv);
284  ASSERT_TRUE(call_success);
285  EXPECT_FALSE(srv.response.ok);
286  }
287 
288  // Successful BEST_EFFORT switch: No-op
289  {
290  SwitchController srv;
291  srv.request.start_controllers.push_back("non_existent_controller");
292  srv.request.stop_controllers.push_back("non_existent_controller");
293  srv.request.strictness = srv.request.BEST_EFFORT;
294  bool call_success = switch_client.call(srv);
295  ASSERT_TRUE(call_success);
296  EXPECT_TRUE(srv.response.ok);
297  }
298 
299  // Successful BEST_EFFORT switch: Partial success, only one started controller
300  {
301  SwitchController srv;
302  srv.request.start_controllers.push_back("my_controller2");
303  srv.request.start_controllers.push_back("non_existent_controller");
304  srv.request.stop_controllers.push_back("non_existent_controller");
305  srv.request.stop_controllers.push_back("my_controller");
306  srv.request.strictness = srv.request.BEST_EFFORT;
307  bool call_success = switch_client.call(srv);
308  ASSERT_TRUE(call_success);
309  EXPECT_TRUE(srv.response.ok);
310  }
311 
312  // Successful BEST_EFFORT switch: Partial success, one started and one stopped controller
313  {
314  SwitchController srv;
315  srv.request.start_controllers.push_back("my_controller");
316  srv.request.start_controllers.push_back("non_existent_controller");
317  srv.request.stop_controllers.push_back("non_existent_controller");
318  srv.request.stop_controllers.push_back("my_controller2");
319  srv.request.strictness = srv.request.BEST_EFFORT;
320  bool call_success = switch_client.call(srv);
321  ASSERT_TRUE(call_success);
322  EXPECT_TRUE(srv.response.ok);
323  }
324 
325  // Back to no running controllers
326  {
327  SwitchController srv;
328  srv.request.stop_controllers.push_back("my_controller");
329  srv.request.strictness = srv.request.STRICT;
330  bool call_success = switch_client.call(srv);
331  ASSERT_TRUE(call_success);
332  EXPECT_TRUE(srv.response.ok);
333  }
334 
335  // Unload controllers
336  {
337  UnloadController srv;
338  srv.request.name = "my_controller";
339  unload_client.call(srv);
340  srv.request.name = "my_controller2";
341  unload_client.call(srv);
342  srv.request.name = "vel_eff_controller";
343  unload_client.call(srv);
344  }
345 }
346 
347 TEST(CMTests, stopBeforeUnload)
348 {
349  ros::NodeHandle nh;
350  ros::ServiceClient load_client = nh.serviceClient<LoadController>("/controller_manager/load_controller");
351  ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
352  ros::ServiceClient switch_client = nh.serviceClient<SwitchController>("/controller_manager/switch_controller");
353 
354  // Load controller
355  {
356  LoadController srv;
357  srv.request.name = "my_controller";
358  bool call_success = load_client.call(srv);
359  ASSERT_TRUE(call_success);
360  EXPECT_TRUE(srv.response.ok);
361  }
362 
363  // Start controller
364  {
365  SwitchController srv;
366  srv.request.start_controllers.push_back("my_controller");
367  srv.request.strictness = srv.request.STRICT;
368  bool call_success = switch_client.call(srv);
369  ASSERT_TRUE(call_success);
370  EXPECT_TRUE(srv.response.ok);
371  }
372 
373  // Try to unload running controller and fail
374  {
375  UnloadController srv;
376  srv.request.name = "my_controller";
377  bool call_success = unload_client.call(srv);
378  ASSERT_TRUE(call_success);
379  EXPECT_FALSE(srv.response.ok);
380  }
381 
382  // Stop controller
383  {
384  SwitchController srv;
385  srv.request.stop_controllers.push_back("my_controller");
386  srv.request.strictness = srv.request.STRICT;
387  bool call_success = switch_client.call(srv);
388  ASSERT_TRUE(call_success);
389  EXPECT_TRUE(srv.response.ok);
390  }
391 
392  // Unload stopped controller
393  {
394  UnloadController srv;
395  srv.request.name = "my_controller";
396  bool call_success = unload_client.call(srv);
397  ASSERT_TRUE(call_success);
398  EXPECT_TRUE(srv.response.ok);
399  }
400 }
401 
402 TEST(CMTests, listControllerTypes)
403 {
404  ros::NodeHandle nh;
405  ros::ServiceClient types_client = nh.serviceClient<ListControllerTypes>("/controller_manager/list_controller_types");
406 
407  ListControllerTypes srv;
408  bool call_success = types_client.call(srv);
409  ASSERT_TRUE(call_success);
410  // Weak test that the number of available types and base classes is not lower than those defined in this test package
411  EXPECT_GE(srv.response.types.size(), 3u);
412  EXPECT_GE(srv.response.base_classes.size(), 3u);
413 }
414 
415 TEST(CMTests, listControllers)
416 {
417  ros::NodeHandle nh;
418  ros::ServiceClient load_client = nh.serviceClient<LoadController>("/controller_manager/load_controller");
419  ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
420  ros::ServiceClient switch_client = nh.serviceClient<SwitchController>("/controller_manager/switch_controller");
421  ros::ServiceClient list_client = nh.serviceClient<ListControllers>("/controller_manager/list_controllers");
422 
423  // Load controllers
424  {
425  LoadController srv;
426  srv.request.name = "my_controller";
427  load_client.call(srv);
428  srv.request.name = "vel_eff_controller";
429  load_client.call(srv);
430  }
431 
432  // Start one controller
433  {
434  SwitchController srv;
435  srv.request.start_controllers.push_back("my_controller");
436  srv.request.strictness = srv.request.STRICT;
437  switch_client.call(srv);
438  }
439 
440  // List controllers
441  {
442  ListControllers srv;
443  bool call_success = list_client.call(srv);
444  ASSERT_TRUE(call_success);
445  ASSERT_EQ(srv.response.controller.size(), 2u);
446 
447  ControllerState state1, state2;
448  if (srv.response.controller[0].name == "my_controller")
449  {
450  state1 = srv.response.controller[0];
451  state2 = srv.response.controller[1];
452  }
453  else
454  {
455  state1 = srv.response.controller[1];
456  state2 = srv.response.controller[0];
457  }
458 
459  EXPECT_EQ(state1.name, "my_controller");
460  EXPECT_EQ(state1.state, "running");
461  EXPECT_EQ(state1.type, "controller_manager_tests/EffortTestController");
462  ASSERT_EQ(state1.claimed_resources.size(), 1u);
463  EXPECT_EQ(state1.claimed_resources[0].hardware_interface, "hardware_interface::EffortJointInterface");
464  ASSERT_EQ(state1.claimed_resources[0].resources.size(), 2u);
465  EXPECT_EQ(state1.claimed_resources[0].resources[0], "hiDOF_joint1");
466  EXPECT_EQ(state1.claimed_resources[0].resources[1], "hiDOF_joint2");
467 
468  EXPECT_EQ(state2.name, "vel_eff_controller");
469  EXPECT_EQ(state2.state, "initialized");
470  EXPECT_EQ(state2.type, "controller_manager_tests/VelEffController");
471  EXPECT_EQ(state2.claimed_resources.size(), 2u);
472  EXPECT_EQ(state2.claimed_resources[0].hardware_interface, "hardware_interface::VelocityJointInterface");
473  ASSERT_EQ(state2.claimed_resources[0].resources.size(), 2u);
474  EXPECT_EQ(state2.claimed_resources[0].resources[0], "hiDOF_joint1");
475  EXPECT_EQ(state2.claimed_resources[0].resources[1], "hiDOF_joint2");
476  EXPECT_EQ(state2.claimed_resources[1].hardware_interface, "hardware_interface::EffortJointInterface");
477  ASSERT_EQ(state2.claimed_resources[1].resources.size(), 1u);
478  EXPECT_EQ(state2.claimed_resources[1].resources[0], "hiDOF_joint3");
479  }
480 
481  // Stop running controller
482  {
483  SwitchController srv;
484  srv.request.stop_controllers.push_back("my_controller");
485  srv.request.strictness = srv.request.STRICT;
486  switch_client.call(srv);
487  }
488 
489  // Unload controllers
490  {
491  UnloadController srv;
492  srv.request.name = "my_controller";
493  unload_client.call(srv);
494  srv.request.name = "vel_eff_controller";
495  unload_client.call(srv);
496  }
497 }
498 
499 TEST(CMTests, extensibleControllers)
500 {
501  ros::NodeHandle nh;
502  ros::ServiceClient load_client = nh.serviceClient<LoadController>("/controller_manager/load_controller");
503  ros::ServiceClient unload_client = nh.serviceClient<UnloadController>("/controller_manager/unload_controller");
504  ros::ServiceClient switch_client = nh.serviceClient<SwitchController>("/controller_manager/switch_controller");
505  ros::ServiceClient list_client = nh.serviceClient<ListControllers>("/controller_manager/list_controllers");
506 
507  // Load controllers.
508  {
509  LoadController srv;
510  srv.request.name = "extensible_controller";
511  load_client.call(srv);
512  srv.request.name = "derived_controller";
513  load_client.call(srv);
514  }
515 
516  // Start the base controller.
517  {
518  SwitchController srv;
519  srv.request.start_controllers.push_back("extensible_controller");
520  srv.request.strictness = srv.request.STRICT;
521  ASSERT_TRUE(switch_client.call(srv));
522  ASSERT_TRUE(srv.response.ok);
523  }
524 
525  // Validate the controller is running and claimed one resource.
526  {
527  ListControllers srv;
528  ASSERT_TRUE(list_client.call(srv));
529  ASSERT_EQ(2u, srv.response.controller.size());
530  ControllerState state = srv.response.controller[0].name == "extensible_controller" ?
531  srv.response.controller[0] : srv.response.controller[1];
532  EXPECT_EQ("extensible_controller", state.name);
533  EXPECT_EQ("running", state.state);
534  ASSERT_EQ(1u, state.claimed_resources.size());
535  }
536 
537  // Start the derived controller instead.
538  {
539  SwitchController srv;
540  srv.request.stop_controllers.push_back("extensible_controller");
541  srv.request.start_controllers.push_back("derived_controller");
542  srv.request.strictness = srv.request.STRICT;
543  ASSERT_TRUE(switch_client.call(srv));
544  ASSERT_TRUE(srv.response.ok);
545  }
546 
547  // Validate the controller is running and claimed two resources.
548  {
549  ListControllers srv;
550  ASSERT_TRUE(list_client.call(srv));
551  ASSERT_EQ(2u, srv.response.controller.size());
552  ControllerState state = srv.response.controller[
553  srv.response.controller[0].name == "derived_controller" ? 0 : 1];
554  EXPECT_EQ("derived_controller", state.name);
555  EXPECT_EQ("running", state.state);
556  ASSERT_EQ(2u, state.claimed_resources.size());
557  }
558 
559  // Stop controller.
560  {
561  SwitchController srv;
562  srv.request.stop_controllers.push_back("derived_controller");
563  srv.request.strictness = srv.request.STRICT;
564  switch_client.call(srv);
565  }
566 
567  // Unload controllers.
568  {
569  UnloadController srv;
570  srv.request.name = "extensible_controller";
571  unload_client.call(srv);
572  srv.request.name = "derived_controller";
573  unload_client.call(srv);
574  }
575 }
576 
577 int main(int argc, char** argv)
578 {
579  testing::InitGoogleTest(&argc, argv);
580  ros::init(argc, argv, "ControllerManagerTestNode");
581 
582  ros::AsyncSpinner spinner(1);
583 
584  // wait for services
585  ROS_INFO("Waiting for service");
586  ros::service::waitForService("/controller_manager/load_controller");
587  ROS_INFO("Start tests");
588  spinner.start();
589  int ret = RUN_ALL_TESTS();
590  spinner.stop();
591  ros::shutdown();
592  return ret;
593 }
main
int main(int argc, char **argv)
Definition: cm_test.cpp:577
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::AsyncSpinner::start
void start()
ros.h
ros::AsyncSpinner
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::shutdown
ROSCPP_DECL void shutdown()
ros::ServiceClient
ros::AsyncSpinner::stop
void stop()
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::service::waitForService
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
TEST
TEST(CMTests, loadUnloadOk)
Definition: cm_test.cpp:43
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle


controller_manager_tests
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Tue Oct 15 2024 02:08:24