|
20 | 20 | #include "controller_manager/controller_manager.hpp"
|
21 | 21 | #include "controller_manager_test_common.hpp"
|
22 | 22 | #include "lifecycle_msgs/msg/state.hpp"
|
| 23 | +#include "test_controller/test_controller.hpp" |
23 | 24 | #include "test_controller_with_interfaces/test_controller_with_interfaces.hpp"
|
24 | 25 |
|
25 | 26 | using ::testing::_;
|
@@ -197,3 +198,137 @@ TEST_F(TestReleaseInterfaces, switch_controllers_same_interface)
|
197 | 198 | abstract_test_controller2.c->get_lifecycle_state().id());
|
198 | 199 | }
|
199 | 200 | }
|
| 201 | + |
| 202 | +class TestReleaseExclusiveInterfaces |
| 203 | +: public ControllerManagerFixture<controller_manager::ControllerManager> |
| 204 | +{ |
| 205 | +public: |
| 206 | + TestReleaseExclusiveInterfaces() |
| 207 | + : ControllerManagerFixture<controller_manager::ControllerManager>( |
| 208 | + std::string(ros2_control_test_assets::urdf_head) + |
| 209 | + std::string(ros2_control_test_assets::hardware_resources_with_exclusive_interface) + |
| 210 | + std::string(ros2_control_test_assets::urdf_tail)) |
| 211 | + { |
| 212 | + } |
| 213 | +}; |
| 214 | + |
| 215 | +TEST_F(TestReleaseExclusiveInterfaces, test_exclusive_interface_deactivation_on_update_error) |
| 216 | +{ |
| 217 | + const std::string controller_type = test_controller::TEST_CONTROLLER_CLASS_NAME; |
| 218 | + |
| 219 | + // Load two controllers of different names |
| 220 | + const std::string controller_name1 = "test_controller1"; |
| 221 | + const std::string controller_name2 = "test_controller2"; |
| 222 | + |
| 223 | + auto test_controller1 = std::make_shared<test_controller::TestController>(); |
| 224 | + controller_interface::InterfaceConfiguration cmd_cfg = { |
| 225 | + controller_interface::interface_configuration_type::INDIVIDUAL, {"joint1/position"}}; |
| 226 | + controller_interface::InterfaceConfiguration state_cfg = { |
| 227 | + controller_interface::interface_configuration_type::INDIVIDUAL, |
| 228 | + {"joint1/position", "joint1/velocity"}}; |
| 229 | + test_controller1->set_command_interface_configuration(cmd_cfg); |
| 230 | + test_controller1->set_state_interface_configuration(state_cfg); |
| 231 | + cm_->add_controller(test_controller1, controller_name1, controller_type); |
| 232 | + |
| 233 | + auto test_controller2 = std::make_shared<test_controller::TestController>(); |
| 234 | + cmd_cfg = {controller_interface::interface_configuration_type::INDIVIDUAL, {"joint2/velocity"}}; |
| 235 | + state_cfg = { |
| 236 | + controller_interface::interface_configuration_type::INDIVIDUAL, |
| 237 | + {"joint2/position", "joint2/velocity"}}; |
| 238 | + test_controller2->set_command_interface_configuration(cmd_cfg); |
| 239 | + test_controller2->set_state_interface_configuration(state_cfg); |
| 240 | + cm_->add_controller(test_controller2, controller_name2, controller_type); |
| 241 | + ASSERT_EQ(2u, cm_->get_loaded_controllers().size()); |
| 242 | + controller_manager::ControllerSpec abstract_test_controller1 = cm_->get_loaded_controllers()[0]; |
| 243 | + controller_manager::ControllerSpec abstract_test_controller2 = cm_->get_loaded_controllers()[1]; |
| 244 | + |
| 245 | + // Configure controllers |
| 246 | + ASSERT_EQ(controller_interface::return_type::OK, cm_->configure_controller(controller_name1)); |
| 247 | + ASSERT_EQ(controller_interface::return_type::OK, cm_->configure_controller(controller_name2)); |
| 248 | + |
| 249 | + ASSERT_EQ( |
| 250 | + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, |
| 251 | + abstract_test_controller1.c->get_lifecycle_state().id()); |
| 252 | + ASSERT_EQ( |
| 253 | + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, |
| 254 | + abstract_test_controller2.c->get_lifecycle_state().id()); |
| 255 | + |
| 256 | + { // Test starting the first and second controller |
| 257 | + RCLCPP_INFO(cm_->get_logger(), "Starting controller #1 and #2"); |
| 258 | + std::vector<std::string> start_controllers = {controller_name1, controller_name2}; |
| 259 | + std::vector<std::string> stop_controllers = {}; |
| 260 | + auto switch_future = std::async( |
| 261 | + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, |
| 262 | + start_controllers, stop_controllers, STRICT, true, rclcpp::Duration(0, 0)); |
| 263 | + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) |
| 264 | + << "switch_controller should be blocking until next update cycle"; |
| 265 | + ControllerManagerRunner cm_runner(this); |
| 266 | + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); |
| 267 | + ASSERT_EQ( |
| 268 | + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, |
| 269 | + abstract_test_controller1.c->get_lifecycle_state().id()); |
| 270 | + ASSERT_EQ( |
| 271 | + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, |
| 272 | + abstract_test_controller2.c->get_lifecycle_state().id()); |
| 273 | + } |
| 274 | + |
| 275 | + // As the external command is Nan, the controller update cycle should return an error and |
| 276 | + // deactivate the controllers |
| 277 | + { |
| 278 | + test_controller1->set_external_commands_for_testing({std::numeric_limits<double>::quiet_NaN()}); |
| 279 | + test_controller2->set_external_commands_for_testing({std::numeric_limits<double>::quiet_NaN()}); |
| 280 | + ControllerManagerRunner cm_runner(this); |
| 281 | + std::this_thread::sleep_for(std::chrono::milliseconds(100)); |
| 282 | + ASSERT_EQ( |
| 283 | + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, |
| 284 | + abstract_test_controller1.c->get_lifecycle_state().id()); |
| 285 | + ASSERT_EQ( |
| 286 | + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, |
| 287 | + abstract_test_controller2.c->get_lifecycle_state().id()); |
| 288 | + } |
| 289 | + |
| 290 | + { // Test starting both controllers but only the second one will pass as the first one has the |
| 291 | + // same external command |
| 292 | + test_controller2->set_external_commands_for_testing({0.0}); |
| 293 | + RCLCPP_INFO(cm_->get_logger(), "Starting controller #1 and #2 again"); |
| 294 | + std::vector<std::string> start_controllers = {controller_name1, controller_name2}; |
| 295 | + std::vector<std::string> stop_controllers = {}; |
| 296 | + auto switch_future = std::async( |
| 297 | + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, |
| 298 | + start_controllers, stop_controllers, STRICT, true, rclcpp::Duration(0, 0)); |
| 299 | + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) |
| 300 | + << "switch_controller should be blocking until next update cycle"; |
| 301 | + ControllerManagerRunner cm_runner(this); |
| 302 | + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); |
| 303 | + std::this_thread::sleep_for(std::chrono::milliseconds(50)); |
| 304 | + ASSERT_EQ( |
| 305 | + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, |
| 306 | + abstract_test_controller1.c->get_lifecycle_state().id()) |
| 307 | + << "Controller 1 current state is " |
| 308 | + << abstract_test_controller1.c->get_lifecycle_state().label(); |
| 309 | + ASSERT_EQ( |
| 310 | + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, |
| 311 | + abstract_test_controller2.c->get_lifecycle_state().id()); |
| 312 | + } |
| 313 | + |
| 314 | + { // Test starting controller 1 and it should work as external command is valid now |
| 315 | + test_controller1->set_external_commands_for_testing({0.0}); |
| 316 | + RCLCPP_INFO(cm_->get_logger(), "Starting controller #1"); |
| 317 | + std::vector<std::string> start_controllers = {controller_name1}; |
| 318 | + std::vector<std::string> stop_controllers = {}; |
| 319 | + auto switch_future = std::async( |
| 320 | + std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_, |
| 321 | + start_controllers, stop_controllers, STRICT, true, rclcpp::Duration(0, 0)); |
| 322 | + ASSERT_EQ(std::future_status::timeout, switch_future.wait_for(std::chrono::milliseconds(100))) |
| 323 | + << "switch_controller should be blocking until next update cycle"; |
| 324 | + ControllerManagerRunner cm_runner(this); |
| 325 | + EXPECT_EQ(controller_interface::return_type::OK, switch_future.get()); |
| 326 | + std::this_thread::sleep_for(std::chrono::milliseconds(50)); |
| 327 | + ASSERT_EQ( |
| 328 | + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, |
| 329 | + abstract_test_controller1.c->get_lifecycle_state().id()); |
| 330 | + ASSERT_EQ( |
| 331 | + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, |
| 332 | + abstract_test_controller2.c->get_lifecycle_state().id()); |
| 333 | + } |
| 334 | +} |
0 commit comments