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> 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);
228 SwitchController srv;
229 srv.request.start_controllers.push_back(
"non_existent_controller");
230 srv.request.strictness = srv.request.STRICT;
231 bool call_success = switch_client.call(srv);
232 ASSERT_TRUE(call_success);
233 EXPECT_FALSE(srv.response.ok);
238 SwitchController srv;
239 srv.request.stop_controllers.push_back(
"non_existent_controller");
240 srv.request.strictness = srv.request.STRICT;
241 bool call_success = switch_client.call(srv);
242 ASSERT_TRUE(call_success);
243 EXPECT_FALSE(srv.response.ok);
248 SwitchController srv;
249 srv.request.start_controllers.push_back(
"my_controller");
250 srv.request.stop_controllers.push_back(
"non_existent_controller");
251 srv.request.strictness = srv.request.STRICT;
252 bool call_success = switch_client.call(srv);
253 ASSERT_TRUE(call_success);
254 EXPECT_FALSE(srv.response.ok);
259 SwitchController srv;
260 srv.request.start_controllers.push_back(
"non_existent_controller");
261 srv.request.stop_controllers.push_back(
"my_controller");
262 srv.request.strictness = srv.request.STRICT;
263 bool call_success = switch_client.call(srv);
264 ASSERT_TRUE(call_success);
265 EXPECT_FALSE(srv.response.ok);
270 SwitchController srv;
271 srv.request.start_controllers.push_back(
"self_conflict_controller");
272 srv.request.strictness = srv.request.STRICT;
273 bool call_success = switch_client.call(srv);
274 ASSERT_TRUE(call_success);
275 EXPECT_FALSE(srv.response.ok);
280 SwitchController srv;
281 srv.request.start_controllers.push_back(
"my_controller");
282 srv.request.start_controllers.push_back(
"my_controller2");
283 srv.request.strictness = srv.request.STRICT;
284 bool call_success = switch_client.call(srv);
285 ASSERT_TRUE(call_success);
286 EXPECT_FALSE(srv.response.ok);
291 SwitchController srv;
292 srv.request.start_controllers.push_back(
"non_existent_controller");
293 srv.request.stop_controllers.push_back(
"non_existent_controller");
294 srv.request.strictness = srv.request.BEST_EFFORT;
295 bool call_success = switch_client.call(srv);
296 ASSERT_TRUE(call_success);
297 EXPECT_TRUE(srv.response.ok);
302 SwitchController srv;
303 srv.request.start_controllers.push_back(
"my_controller2");
304 srv.request.start_controllers.push_back(
"non_existent_controller");
305 srv.request.stop_controllers.push_back(
"non_existent_controller");
306 srv.request.stop_controllers.push_back(
"my_controller");
307 srv.request.strictness = srv.request.BEST_EFFORT;
308 bool call_success = switch_client.call(srv);
309 ASSERT_TRUE(call_success);
310 EXPECT_TRUE(srv.response.ok);
315 SwitchController srv;
316 srv.request.start_controllers.push_back(
"my_controller");
317 srv.request.start_controllers.push_back(
"non_existent_controller");
318 srv.request.stop_controllers.push_back(
"non_existent_controller");
319 srv.request.stop_controllers.push_back(
"my_controller2");
320 srv.request.strictness = srv.request.BEST_EFFORT;
321 bool call_success = switch_client.call(srv);
322 ASSERT_TRUE(call_success);
323 EXPECT_TRUE(srv.response.ok);
328 SwitchController srv;
329 srv.request.stop_controllers.push_back(
"my_controller");
330 srv.request.strictness = srv.request.STRICT;
331 bool call_success = switch_client.call(srv);
332 ASSERT_TRUE(call_success);
333 EXPECT_TRUE(srv.response.ok);
338 UnloadController srv;
339 srv.request.name =
"my_controller";
340 unload_client.call(srv);
341 srv.request.name =
"my_controller2";
342 unload_client.call(srv);
343 srv.request.name =
"vel_eff_controller";
344 unload_client.call(srv);
348 TEST(CMTests, stopBeforeUnload)
358 srv.request.name =
"my_controller";
359 bool call_success = load_client.
call(srv);
360 ASSERT_TRUE(call_success);
361 EXPECT_TRUE(srv.response.ok);
366 SwitchController srv;
367 srv.request.start_controllers.push_back(
"my_controller");
368 srv.request.strictness = srv.request.STRICT;
369 bool call_success = switch_client.call(srv);
370 ASSERT_TRUE(call_success);
371 EXPECT_TRUE(srv.response.ok);
376 UnloadController srv;
377 srv.request.name =
"my_controller";
378 bool call_success = unload_client.call(srv);
379 ASSERT_TRUE(call_success);
380 EXPECT_FALSE(srv.response.ok);
385 SwitchController srv;
386 srv.request.stop_controllers.push_back(
"my_controller");
387 srv.request.strictness = srv.request.STRICT;
388 bool call_success = switch_client.call(srv);
389 ASSERT_TRUE(call_success);
390 EXPECT_TRUE(srv.response.ok);
395 UnloadController srv;
396 srv.request.name =
"my_controller";
397 bool call_success = unload_client.call(srv);
398 ASSERT_TRUE(call_success);
399 EXPECT_TRUE(srv.response.ok);
403 TEST(CMTests, listControllerTypes)
408 ListControllerTypes srv;
409 bool call_success = types_client.
call(srv);
410 ASSERT_TRUE(call_success);
412 EXPECT_GE(srv.response.types.size(), 3);
413 EXPECT_GE(srv.response.base_classes.size(), 3);
427 srv.request.name =
"my_controller";
428 load_client.
call(srv);
429 srv.request.name =
"vel_eff_controller";
430 load_client.
call(srv);
435 SwitchController srv;
436 srv.request.start_controllers.push_back(
"my_controller");
437 srv.request.strictness = srv.request.STRICT;
438 switch_client.call(srv);
444 bool call_success = list_client.call(srv);
445 ASSERT_TRUE(call_success);
446 ASSERT_EQ(srv.response.controller.size(), 2);
448 ControllerState state1, state2;
449 if (srv.response.controller[0].name ==
"my_controller")
451 state1 = srv.response.controller[0];
452 state2 = srv.response.controller[1];
456 state1 = srv.response.controller[1];
457 state2 = srv.response.controller[0];
460 EXPECT_EQ(state1.name,
"my_controller");
461 EXPECT_EQ(state1.state,
"running");
462 EXPECT_EQ(state1.type,
"controller_manager_tests/EffortTestController");
463 ASSERT_EQ(state1.claimed_resources.size(), 1);
464 EXPECT_EQ(state1.claimed_resources[0].hardware_interface,
"hardware_interface::EffortJointInterface");
465 ASSERT_EQ(state1.claimed_resources[0].resources.size(), 2);
466 EXPECT_EQ(state1.claimed_resources[0].resources[0],
"hiDOF_joint1");
467 EXPECT_EQ(state1.claimed_resources[0].resources[1],
"hiDOF_joint2");
469 EXPECT_EQ(state2.name,
"vel_eff_controller");
470 EXPECT_EQ(state2.state,
"stopped");
471 EXPECT_EQ(state2.type,
"controller_manager_tests/VelEffController");
472 EXPECT_EQ(state2.claimed_resources.size(), 2);
473 EXPECT_EQ(state2.claimed_resources[0].hardware_interface,
"hardware_interface::VelocityJointInterface");
474 ASSERT_EQ(state2.claimed_resources[0].resources.size(), 2);
475 EXPECT_EQ(state2.claimed_resources[0].resources[0],
"hiDOF_joint1");
476 EXPECT_EQ(state2.claimed_resources[0].resources[1],
"hiDOF_joint2");
477 EXPECT_EQ(state2.claimed_resources[1].hardware_interface,
"hardware_interface::EffortJointInterface");
478 ASSERT_EQ(state2.claimed_resources[1].resources.size(), 1);
479 EXPECT_EQ(state2.claimed_resources[1].resources[0],
"hiDOF_joint3");
484 SwitchController srv;
485 srv.request.stop_controllers.push_back(
"my_controller");
486 srv.request.strictness = srv.request.STRICT;
487 switch_client.call(srv);
492 UnloadController srv;
493 srv.request.name =
"my_controller";
494 unload_client.call(srv);
495 srv.request.name =
"vel_eff_controller";
496 unload_client.call(srv);
500 int main(
int argc,
char** argv)
502 testing::InitGoogleTest(&argc, argv);
503 ros::init(argc, argv,
"ControllerManagerTestNode");
512 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)