33 #include <gtest/gtest.h> 35 #include <controller_manager_msgs/ListControllers.h> 36 #include <controller_manager_msgs/ListControllerTypes.h> 37 #include <controller_manager_msgs/LoadController.h> 38 #include <controller_manager_msgs/SwitchController.h> 39 #include <controller_manager_msgs/UnloadController.h> 44 TEST(CMTests, loadUnloadOk)
53 srv.request.name =
"my_controller";
54 bool call_success = load_client.
call(srv);
55 ASSERT_TRUE(call_success);
56 EXPECT_TRUE(srv.response.ok);
63 srv.request.name =
"vel_eff_controller";
64 bool call_success = load_client.
call(srv);
65 ASSERT_TRUE(call_success);
66 EXPECT_TRUE(srv.response.ok);
73 srv.request.name =
"optional_interfaces_controller";
74 bool call_success = load_client.
call(srv);
75 ASSERT_TRUE(call_success);
76 EXPECT_TRUE(srv.response.ok);
82 srv.request.name =
"my_controller";
83 bool call_success = unload_client.call(srv);
84 ASSERT_TRUE(call_success);
85 EXPECT_TRUE(srv.response.ok);
91 srv.request.name =
"vel_eff_controller";
92 bool call_success = unload_client.call(srv);
93 ASSERT_TRUE(call_success);
94 EXPECT_TRUE(srv.response.ok);
98 srv.request.name =
"optional_interfaces_controller";
99 bool call_success = unload_client.call(srv);
100 ASSERT_TRUE(call_success);
101 EXPECT_TRUE(srv.response.ok);
114 srv.request.name =
"nonexistent_controller";
115 bool call_success = load_client.
call(srv);
116 ASSERT_TRUE(call_success);
117 EXPECT_FALSE(srv.response.ok);
123 srv.request.name =
"non_existent_interface_controller";
124 bool call_success = load_client.
call(srv);
125 ASSERT_TRUE(call_success);
126 EXPECT_FALSE(srv.response.ok);
132 srv.request.name =
"non_existent_resource_controller";
133 bool call_success = load_client.
call(srv);
134 ASSERT_TRUE(call_success);
135 EXPECT_FALSE(srv.response.ok);
142 srv.request.name =
"non_existing_multi_interface_controller";
143 bool call_success = load_client.
call(srv);
144 ASSERT_TRUE(call_success);
145 EXPECT_FALSE(srv.response.ok);
150 UnloadController srv;
151 srv.request.name =
"my_controller";
152 bool call_success = unload_client.call(srv);
153 ASSERT_TRUE(call_success);
154 EXPECT_FALSE(srv.response.ok);
158 TEST(CMTests, switchController)
168 srv.request.name =
"my_controller";
169 load_client.
call(srv);
170 srv.request.name =
"my_controller2";
171 load_client.
call(srv);
172 srv.request.name =
"vel_eff_controller";
173 load_client.
call(srv);
174 srv.request.name =
"self_conflict_controller";
175 load_client.
call(srv);
180 SwitchController srv;
181 srv.request.start_controllers.push_back(
"my_controller");
182 srv.request.strictness = srv.request.STRICT;
183 bool call_success = switch_client.call(srv);
184 ASSERT_TRUE(call_success);
185 EXPECT_TRUE(srv.response.ok);
190 SwitchController srv;
191 srv.request.stop_controllers.push_back(
"my_controller");
192 srv.request.strictness = srv.request.STRICT;
193 bool call_success = switch_client.call(srv);
194 ASSERT_TRUE(call_success);
195 EXPECT_TRUE(srv.response.ok);
200 SwitchController srv;
201 srv.request.start_controllers.push_back(
"vel_eff_controller");
202 srv.request.strictness = srv.request.STRICT;
203 bool call_success = switch_client.call(srv);
204 ASSERT_TRUE(call_success);
205 EXPECT_TRUE(srv.response.ok);
210 SwitchController srv;
211 srv.request.start_controllers.push_back(
"my_controller");
212 srv.request.stop_controllers.push_back(
"vel_eff_controller");
213 srv.request.strictness = srv.request.STRICT;
214 bool call_success = switch_client.call(srv);
215 ASSERT_TRUE(call_success);
216 EXPECT_TRUE(srv.response.ok);
221 SwitchController srv;
222 srv.request.stop_controllers.push_back(
"my_controller");
223 srv.request.strictness = srv.request.STRICT;
224 bool call_success = switch_client.call(srv);
225 ASSERT_TRUE(call_success);
226 EXPECT_TRUE(srv.response.ok);
231 SwitchController srv;
232 srv.request.start_controllers.push_back(
"non_existent_controller");
233 srv.request.strictness = srv.request.STRICT;
234 bool call_success = switch_client.call(srv);
235 ASSERT_TRUE(call_success);
236 EXPECT_FALSE(srv.response.ok);
241 SwitchController srv;
242 srv.request.stop_controllers.push_back(
"non_existent_controller");
243 srv.request.strictness = srv.request.STRICT;
244 bool call_success = switch_client.call(srv);
245 ASSERT_TRUE(call_success);
246 EXPECT_FALSE(srv.response.ok);
251 SwitchController srv;
252 srv.request.start_controllers.push_back(
"my_controller");
253 srv.request.stop_controllers.push_back(
"non_existent_controller");
254 srv.request.strictness = srv.request.STRICT;
255 bool call_success = switch_client.call(srv);
256 ASSERT_TRUE(call_success);
257 EXPECT_FALSE(srv.response.ok);
262 SwitchController srv;
263 srv.request.start_controllers.push_back(
"non_existent_controller");
264 srv.request.stop_controllers.push_back(
"my_controller");
265 srv.request.strictness = srv.request.STRICT;
266 bool call_success = switch_client.call(srv);
267 ASSERT_TRUE(call_success);
268 EXPECT_FALSE(srv.response.ok);
273 SwitchController srv;
274 srv.request.start_controllers.push_back(
"self_conflict_controller");
275 srv.request.strictness = srv.request.STRICT;
276 bool call_success = switch_client.call(srv);
277 ASSERT_TRUE(call_success);
278 EXPECT_FALSE(srv.response.ok);
283 SwitchController srv;
284 srv.request.start_controllers.push_back(
"my_controller");
285 srv.request.start_controllers.push_back(
"my_controller2");
286 srv.request.strictness = srv.request.STRICT;
287 bool call_success = switch_client.call(srv);
288 ASSERT_TRUE(call_success);
289 EXPECT_FALSE(srv.response.ok);
294 SwitchController srv;
295 srv.request.start_controllers.push_back(
"non_existent_controller");
296 srv.request.stop_controllers.push_back(
"non_existent_controller");
297 srv.request.strictness = srv.request.BEST_EFFORT;
298 bool call_success = switch_client.call(srv);
299 ASSERT_TRUE(call_success);
300 EXPECT_TRUE(srv.response.ok);
305 SwitchController srv;
306 srv.request.start_controllers.push_back(
"my_controller2");
307 srv.request.start_controllers.push_back(
"non_existent_controller");
308 srv.request.stop_controllers.push_back(
"non_existent_controller");
309 srv.request.stop_controllers.push_back(
"my_controller");
310 srv.request.strictness = srv.request.BEST_EFFORT;
311 bool call_success = switch_client.call(srv);
312 ASSERT_TRUE(call_success);
313 EXPECT_TRUE(srv.response.ok);
318 SwitchController srv;
319 srv.request.start_controllers.push_back(
"my_controller");
320 srv.request.start_controllers.push_back(
"non_existent_controller");
321 srv.request.stop_controllers.push_back(
"non_existent_controller");
322 srv.request.stop_controllers.push_back(
"my_controller2");
323 srv.request.strictness = srv.request.BEST_EFFORT;
324 bool call_success = switch_client.call(srv);
325 ASSERT_TRUE(call_success);
326 EXPECT_TRUE(srv.response.ok);
331 SwitchController srv;
332 srv.request.stop_controllers.push_back(
"my_controller");
333 srv.request.strictness = srv.request.STRICT;
334 bool call_success = switch_client.call(srv);
335 ASSERT_TRUE(call_success);
336 EXPECT_TRUE(srv.response.ok);
341 UnloadController srv;
342 srv.request.name =
"my_controller";
343 unload_client.call(srv);
344 srv.request.name =
"my_controller2";
345 unload_client.call(srv);
346 srv.request.name =
"vel_eff_controller";
347 unload_client.call(srv);
348 srv.request.name =
"self_conflict_controller";
349 unload_client.call(srv);
353 TEST(CMTests, stopBeforeUnload)
363 srv.request.name =
"my_controller";
364 bool call_success = load_client.
call(srv);
365 ASSERT_TRUE(call_success);
366 EXPECT_TRUE(srv.response.ok);
371 SwitchController srv;
372 srv.request.start_controllers.push_back(
"my_controller");
373 srv.request.strictness = srv.request.STRICT;
374 bool call_success = switch_client.call(srv);
375 ASSERT_TRUE(call_success);
376 EXPECT_TRUE(srv.response.ok);
381 UnloadController srv;
382 srv.request.name =
"my_controller";
383 bool call_success = unload_client.call(srv);
384 ASSERT_TRUE(call_success);
385 EXPECT_FALSE(srv.response.ok);
390 SwitchController srv;
391 srv.request.stop_controllers.push_back(
"my_controller");
392 srv.request.strictness = srv.request.STRICT;
393 bool call_success = switch_client.call(srv);
394 ASSERT_TRUE(call_success);
395 EXPECT_TRUE(srv.response.ok);
400 UnloadController srv;
401 srv.request.name =
"my_controller";
402 bool call_success = unload_client.call(srv);
403 ASSERT_TRUE(call_success);
404 EXPECT_TRUE(srv.response.ok);
408 TEST(CMTests, listControllerTypes)
413 ListControllerTypes srv;
414 bool call_success = types_client.
call(srv);
415 ASSERT_TRUE(call_success);
417 EXPECT_GE(srv.response.types.size(), 3);
418 EXPECT_GE(srv.response.base_classes.size(), 3);
432 srv.request.name =
"my_controller";
433 load_client.
call(srv);
434 srv.request.name =
"vel_eff_controller";
435 load_client.
call(srv);
440 SwitchController srv;
441 srv.request.start_controllers.push_back(
"my_controller");
442 srv.request.strictness = srv.request.STRICT;
443 switch_client.call(srv);
449 bool call_success = list_client.call(srv);
450 ASSERT_TRUE(call_success);
451 ASSERT_EQ(srv.response.controller.size(), 2);
453 ControllerState state1, state2;
454 if (srv.response.controller[0].name ==
"my_controller")
456 state1 = srv.response.controller[0];
457 state2 = srv.response.controller[1];
461 state1 = srv.response.controller[1];
462 state2 = srv.response.controller[0];
465 EXPECT_EQ(state1.name,
"my_controller");
466 EXPECT_EQ(state1.state,
"running");
467 EXPECT_EQ(state1.type,
"controller_manager_tests/EffortTestController");
468 ASSERT_EQ(state1.claimed_resources.size(), 1);
469 EXPECT_EQ(state1.claimed_resources[0].hardware_interface,
"hardware_interface::EffortJointInterface");
470 ASSERT_EQ(state1.claimed_resources[0].resources.size(), 2);
471 EXPECT_EQ(state1.claimed_resources[0].resources[0],
"hiDOF_joint1");
472 EXPECT_EQ(state1.claimed_resources[0].resources[1],
"hiDOF_joint2");
474 EXPECT_EQ(state2.name,
"vel_eff_controller");
475 EXPECT_EQ(state2.state,
"stopped");
476 EXPECT_EQ(state2.type,
"controller_manager_tests/VelEffController");
477 EXPECT_EQ(state2.claimed_resources.size(), 2);
478 EXPECT_EQ(state2.claimed_resources[0].hardware_interface,
"hardware_interface::VelocityJointInterface");
479 ASSERT_EQ(state2.claimed_resources[0].resources.size(), 2);
480 EXPECT_EQ(state2.claimed_resources[0].resources[0],
"test_joint1");
481 EXPECT_EQ(state2.claimed_resources[0].resources[1],
"test_joint2");
482 EXPECT_EQ(state2.claimed_resources[1].hardware_interface,
"hardware_interface::EffortJointInterface");
483 ASSERT_EQ(state2.claimed_resources[1].resources.size(), 1);
484 EXPECT_EQ(state2.claimed_resources[1].resources[0],
"test_joint4");
489 SwitchController srv;
490 srv.request.stop_controllers.push_back(
"my_controller");
491 srv.request.strictness = srv.request.STRICT;
492 switch_client.call(srv);
497 UnloadController srv;
498 srv.request.name =
"my_controller";
499 unload_client.call(srv);
500 srv.request.name =
"vel_eff_controller";
501 unload_client.call(srv);
505 int main(
int argc,
char** argv)
507 testing::InitGoogleTest(&argc, argv);
508 ros::init(argc, argv,
"ControllerManagerTestNode");
517 int ret = RUN_ALL_TESTS();
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)
ROSCPP_DECL void shutdown()
int main(int argc, char **argv)
TEST(CMTests, loadUnloadOk)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)