32 #include <gtest/gtest.h>
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>
41 using namespace controller_manager_msgs;
43 TEST(CMTests, loadUnloadOk)
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
157 TEST(CMTests, switchController)
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
347 TEST(CMTests, stopBeforeUnload)
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);
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);
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);
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);
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);
402 TEST(CMTests, listControllerTypes)
407 ListControllerTypes srv;
408 bool call_success = types_client.
call(srv);
409 ASSERT_TRUE(call_success);
411 EXPECT_GE(srv.response.types.size(), 3u);
412 EXPECT_GE(srv.response.base_classes.size(), 3u);
426 srv.request.name =
"my_controller";
427 load_client.
call(srv);
428 srv.request.name =
"vel_eff_controller";
429 load_client.
call(srv);
434 SwitchController srv;
435 srv.request.start_controllers.push_back(
"my_controller");
436 srv.request.strictness = srv.request.STRICT;
437 switch_client.call(srv);
443 bool call_success = list_client.call(srv);
444 ASSERT_TRUE(call_success);
445 ASSERT_EQ(srv.response.controller.size(), 2u);
447 ControllerState state1, state2;
448 if (srv.response.controller[0].name ==
"my_controller")
450 state1 = srv.response.controller[0];
451 state2 = srv.response.controller[1];
455 state1 = srv.response.controller[1];
456 state2 = srv.response.controller[0];
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");
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");
483 SwitchController srv;
484 srv.request.stop_controllers.push_back(
"my_controller");
485 srv.request.strictness = srv.request.STRICT;
486 switch_client.call(srv);
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);
499 TEST(CMTests, extensibleControllers)
510 srv.request.name =
"extensible_controller";
511 load_client.
call(srv);
512 srv.request.name =
"derived_controller";
513 load_client.
call(srv);
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);
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());
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);
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());
561 SwitchController srv;
562 srv.request.stop_controllers.push_back(
"derived_controller");
563 srv.request.strictness = srv.request.STRICT;
564 switch_client.call(srv);
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);
577 int main(
int argc,
char** argv)
579 testing::InitGoogleTest(&argc, argv);
580 ros::init(argc, argv,
"ControllerManagerTestNode");
589 int ret = RUN_ALL_TESTS();