@@ -456,6 +456,8 @@ TEST_F(TestControllerManagerSrvs, unload_controller_srv)
456456
457457 result = call_service_and_wait (*client, request, srv_executor, true );
458458 ASSERT_TRUE (result->ok );
459+ EXPECT_EQ (
460+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
459461 EXPECT_EQ (0u , cm_->get_loaded_controllers ().size ());
460462}
461463
@@ -488,6 +490,8 @@ TEST_F(TestControllerManagerSrvs, robot_description_on_load_and_unload_controlle
488490 auto unload_request = std::make_shared<controller_manager_msgs::srv::UnloadController::Request>();
489491 unload_request->name = test_controller::TEST_CONTROLLER_NAME;
490492 auto result = call_service_and_wait (*unload_client, unload_request, srv_executor, true );
493+ EXPECT_EQ (
494+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
491495 EXPECT_EQ (0u , cm_->get_loaded_controllers ().size ());
492496
493497 // now load it and check if it got the new robot description
@@ -508,6 +512,9 @@ TEST_F(TestControllerManagerSrvs, configure_controller_srv)
508512 rclcpp::Client<controller_manager_msgs::srv::ConfigureController>::SharedPtr client =
509513 srv_node->create_client <controller_manager_msgs::srv::ConfigureController>(
510514 " test_controller_manager/configure_controller" );
515+ rclcpp::Client<controller_manager_msgs::srv::UnloadController>::SharedPtr unload_client =
516+ srv_node->create_client <controller_manager_msgs::srv::UnloadController>(
517+ " test_controller_manager/unload_controller" );
511518
512519 auto request = std::make_shared<controller_manager_msgs::srv::ConfigureController::Request>();
513520 request->name = test_controller::TEST_CONTROLLER_NAME;
@@ -526,6 +533,15 @@ TEST_F(TestControllerManagerSrvs, configure_controller_srv)
526533 EXPECT_EQ (
527534 lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
528535 cm_->get_loaded_controllers ()[0 ].c ->get_state ().id ());
536+ EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state ().id ());
537+
538+ // now unload the controller and check the state
539+ auto unload_request = std::make_shared<controller_manager_msgs::srv::UnloadController::Request>();
540+ unload_request->name = test_controller::TEST_CONTROLLER_NAME;
541+ ASSERT_TRUE (call_service_and_wait (*unload_client, unload_request, srv_executor, true )->ok );
542+ EXPECT_EQ (
543+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
544+ EXPECT_EQ (0u , cm_->get_loaded_controllers ().size ());
529545}
530546
531547TEST_F (TestControllerManagerSrvs, list_sorted_chained_controllers)
0 commit comments