@@ -434,6 +434,68 @@ TEST_F(TestControllerManagerSrvs, load_controller_srv)
434
434
cm_->get_loaded_controllers ()[0 ].c ->get_state ().id ());
435
435
}
436
436
437
+ TEST_F (TestControllerManagerSrvs, cleanup_controller_srv)
438
+ {
439
+ rclcpp::executors::SingleThreadedExecutor srv_executor;
440
+ rclcpp::Node::SharedPtr srv_node = std::make_shared<rclcpp::Node>(" srv_client" );
441
+ srv_executor.add_node (srv_node);
442
+ rclcpp::Client<controller_manager_msgs::srv::CleanupController>::SharedPtr client =
443
+ srv_node->create_client <controller_manager_msgs::srv::CleanupController>(
444
+ " test_controller_manager/cleanup_controller" );
445
+
446
+ auto request = std::make_shared<controller_manager_msgs::srv::CleanupController::Request>();
447
+ request->name = test_controller::TEST_CONTROLLER_NAME;
448
+
449
+ // variation - 1:
450
+ // scenario: call the cleanup service when no controllers are loaded
451
+ // expected: it should return ERROR as no controllers will be found to cleanup
452
+ auto result = call_service_and_wait (*client, request, srv_executor);
453
+ ASSERT_FALSE (result->ok ) << " Controller not loaded: " << request->name ;
454
+
455
+ // variation - 2:
456
+ // scenario: call the cleanup service when one controller is loaded
457
+ // expected: it should return OK as one controller will be found to cleanup
458
+ auto test_controller = std::make_shared<TestController>();
459
+ auto abstract_test_controller = cm_->add_controller (
460
+ test_controller, test_controller::TEST_CONTROLLER_NAME,
461
+ test_controller::TEST_CONTROLLER_CLASS_NAME);
462
+ EXPECT_EQ (1u , cm_->get_loaded_controllers ().size ());
463
+
464
+ result = call_service_and_wait (*client, request, srv_executor, true );
465
+ ASSERT_TRUE (result->ok );
466
+ EXPECT_EQ (1u , cm_->get_loaded_controllers ().size ());
467
+
468
+ // variation - 3:
469
+ // scenario: call the cleanup service when controller state is ACTIVE
470
+ // expected: it should return ERROR as cleanup is restricted for ACTIVE controllers
471
+ test_controller = std::dynamic_pointer_cast<TestController>(cm_->load_controller (
472
+ test_controller::TEST_CONTROLLER_NAME, test_controller::TEST_CONTROLLER_CLASS_NAME));
473
+ cm_->configure_controller (test_controller::TEST_CONTROLLER_NAME);
474
+ // activate controllers
475
+ cm_->switch_controller (
476
+ {test_controller::TEST_CONTROLLER_NAME}, {},
477
+ controller_manager_msgs::srv::SwitchController::Request::STRICT, true , rclcpp::Duration (0 , 0 ));
478
+ EXPECT_EQ (
479
+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
480
+ cm_->get_loaded_controllers ()[0 ].c ->get_state ().id ());
481
+ result = call_service_and_wait (*client, request, srv_executor, true );
482
+ ASSERT_FALSE (result->ok ) << " Controller can not be cleaned in active state: " << request->name ;
483
+ EXPECT_EQ (1u , cm_->get_loaded_controllers ().size ());
484
+
485
+ // variation - 4:
486
+ // scenario: call the cleanup service when controller state is INACTIVE
487
+ // expected: it should return OK as cleanup will be done for INACTIVE controllers
488
+ cm_->switch_controller (
489
+ {}, {test_controller::TEST_CONTROLLER_NAME},
490
+ controller_manager_msgs::srv::SwitchController::Request::STRICT, true , rclcpp::Duration (0 , 0 ));
491
+ EXPECT_EQ (
492
+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
493
+ cm_->get_loaded_controllers ()[0 ].c ->get_state ().id ());
494
+ result = call_service_and_wait (*client, request, srv_executor, true );
495
+ ASSERT_TRUE (result->ok ) << " Controller cleaned in inactive state: " << request->name ;
496
+ EXPECT_EQ (1u , cm_->get_loaded_controllers ().size ());
497
+ }
498
+
437
499
TEST_F (TestControllerManagerSrvs, unload_controller_srv)
438
500
{
439
501
rclcpp::executors::SingleThreadedExecutor srv_executor;
0 commit comments