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