@@ -462,9 +462,57 @@ TEST_F(TestControllerManagerSrvs, unload_controller_srv)
462462
463463 result = call_service_and_wait (*client, request, srv_executor, true );
464464 ASSERT_TRUE (result->ok );
465+ EXPECT_EQ (
466+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
467+ EXPECT_EQ (0u , cm_->get_loaded_controllers ().size ());
468+ }
469+
470+ <<<<<<< HEAD
471+ =======
472+ TEST_F (TestControllerManagerSrvs, robot_description_on_load_and_unload_controller)
473+ {
474+ rclcpp::executors::SingleThreadedExecutor srv_executor;
475+ rclcpp::Node::SharedPtr srv_node = std::make_shared<rclcpp::Node>(" srv_client" );
476+ srv_executor.add_node (srv_node);
477+ rclcpp::Client<controller_manager_msgs::srv::UnloadController>::SharedPtr unload_client =
478+ srv_node->create_client <controller_manager_msgs::srv::UnloadController>(
479+ " test_controller_manager/unload_controller" );
480+
481+ auto test_controller = std::make_shared<TestController>();
482+ auto abstract_test_controller = cm_->add_controller (
483+ test_controller, test_controller::TEST_CONTROLLER_NAME,
484+ test_controller::TEST_CONTROLLER_CLASS_NAME);
485+ EXPECT_EQ (1u , cm_->get_loaded_controllers ().size ());
486+
487+ // check the robot description
488+ ASSERT_EQ (ros2_control_test_assets::minimal_robot_urdf, test_controller->get_robot_description ());
489+
490+ // Now change the robot description and then see that the controller maintains the old URDF until
491+ // it is unloaded and loaded again
492+ auto msg = std_msgs::msg::String ();
493+ msg.data = ros2_control_test_assets::minimal_robot_missing_state_keys_urdf;
494+ cm_->robot_description_callback (msg);
495+ ASSERT_EQ (ros2_control_test_assets::minimal_robot_urdf, test_controller->get_robot_description ());
496+
497+ // now unload and load the controller and see if the controller gets the new robot description
498+ auto unload_request = std::make_shared<controller_manager_msgs::srv::UnloadController::Request>();
499+ unload_request->name = test_controller::TEST_CONTROLLER_NAME;
500+ auto result = call_service_and_wait (*unload_client, unload_request, srv_executor, true );
501+ EXPECT_EQ (
502+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
465503 EXPECT_EQ (0u , cm_->get_loaded_controllers ().size ());
504+
505+ // now load it and check if it got the new robot description
506+ cm_->add_controller (
507+ test_controller, test_controller::TEST_CONTROLLER_NAME,
508+ test_controller::TEST_CONTROLLER_CLASS_NAME);
509+ EXPECT_EQ (1u , cm_->get_loaded_controllers ().size ());
510+ ASSERT_EQ (
511+ ros2_control_test_assets::minimal_robot_missing_state_keys_urdf,
512+ test_controller->get_robot_description ());
466513}
467514
515+ >>>>>>> 6f57faf (check for state of the controller node before cleanup (#1363 ))
468516TEST_F(TestControllerManagerSrvs, configure_controller_srv)
469517{
470518 rclcpp::executors::SingleThreadedExecutor srv_executor;
@@ -473,6 +521,9 @@ TEST_F(TestControllerManagerSrvs, configure_controller_srv)
473521 rclcpp::Client<controller_manager_msgs::srv::ConfigureController>::SharedPtr client =
474522 srv_node->create_client <controller_manager_msgs::srv::ConfigureController>(
475523 " test_controller_manager/configure_controller" );
524+ rclcpp::Client<controller_manager_msgs::srv::UnloadController>::SharedPtr unload_client =
525+ srv_node->create_client <controller_manager_msgs::srv::UnloadController>(
526+ " test_controller_manager/unload_controller" );
476527
477528 auto request = std::make_shared<controller_manager_msgs::srv::ConfigureController::Request>();
478529 request->name = test_controller::TEST_CONTROLLER_NAME;
@@ -491,6 +542,15 @@ TEST_F(TestControllerManagerSrvs, configure_controller_srv)
491542 EXPECT_EQ (
492543 lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
493544 cm_->get_loaded_controllers ()[0 ].c ->get_state ().id ());
545+ EXPECT_EQ (lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, test_controller->get_state ().id ());
546+
547+ // now unload the controller and check the state
548+ auto unload_request = std::make_shared<controller_manager_msgs::srv::UnloadController::Request>();
549+ unload_request->name = test_controller::TEST_CONTROLLER_NAME;
550+ ASSERT_TRUE (call_service_and_wait (*unload_client, unload_request, srv_executor, true )->ok );
551+ EXPECT_EQ (
552+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, test_controller->get_state ().id ());
553+ EXPECT_EQ (0u , cm_->get_loaded_controllers ().size ());
494554}
495555
496556TEST_F (TestControllerManagerSrvs, list_sorted_chained_controllers)
0 commit comments