diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index fb9bce879a..b05801a657 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -1013,105 +1013,165 @@ controller_interface::return_type ControllerManager::switch_controller( const std::vector & controllers = rt_controllers_wrapper_.get_updated_list(guard); - // if a preceding controller is deactivated, all first-level controllers should be switched 'from' - // chained mode - propagate_deactivation_of_chained_mode(controllers); - - // check if controllers should be switched 'to' chained mode when controllers are activated - for (auto ctrl_it = activate_request_.begin(); ctrl_it != activate_request_.end(); ++ctrl_it) + enum class CreateRequestResult { - auto controller_it = std::find_if( - controllers.begin(), controllers.end(), - std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); - controller_interface::return_type status = controller_interface::return_type::OK; + OK, + ERROR, + RETRY + }; - // if controller is not inactive then do not do any following-controllers checks - if (!is_controller_inactive(controller_it->c)) + const auto check_de_activate_request_and_create_chained_mode_request = + [this, &strictness, &controllers]() -> CreateRequestResult + { + const auto clear_chained_mode_requests = [this]() { - RCLCPP_WARN( - get_logger(), - "Controller with name '%s' is not inactive so its following " - "controllers do not have to be checked, because it cannot be activated.", - controller_it->info.name.c_str()); - status = controller_interface::return_type::ERROR; - } - else + // Set these interfaces as unavailable when clearing requests to avoid leaving them in + // available state without the controller being in active state + for (const auto & controller_name : to_chained_mode_request_) + { + resource_manager_->make_controller_reference_interfaces_unavailable(controller_name); + } + to_chained_mode_request_.clear(); + from_chained_mode_request_.clear(); + }; + + // if a preceding controller is deactivated, all first-level controllers should be switched + // 'from' chained mode + propagate_deactivation_of_chained_mode(controllers); + + // check if controllers should be switched 'to' chained mode when controllers are activated + for (auto ctrl_it = activate_request_.begin(); ctrl_it != activate_request_.end(); ++ctrl_it) { - status = check_following_controllers_for_activate(controllers, strictness, controller_it); + auto controller_it = std::find_if( + controllers.begin(), controllers.end(), + std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); + controller_interface::return_type status = controller_interface::return_type::OK; + + // if controller is not inactive then do not do any following-controllers checks + if (!is_controller_inactive(controller_it->c)) + { + RCLCPP_WARN( + get_logger(), + "Controller with name '%s' is not inactive so its following " + "controllers do not have to be checked, because it cannot be activated.", + controller_it->info.name.c_str()); + status = controller_interface::return_type::ERROR; + } + else + { + status = check_following_controllers_for_activate(controllers, strictness, controller_it); + } + + if (status != controller_interface::return_type::OK) + { + RCLCPP_WARN( + get_logger(), + "Could not activate controller with name '%s'. Check above warnings for more details. " + "Check the state of the controllers and their required interfaces using " + "`ros2 control list_controllers -v` CLI to get more information.", + (*ctrl_it).c_str()); + if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT) + { + // TODO(destogl): automatic manipulation of the chain: + // || strictness == + // controller_manager_msgs::srv::SwitchController::Request::MANIPULATE_CONTROLLERS_CHAIN); + // remove controller that can not be activated from the activation request and step-back + // iterator to correctly step to the next element in the list in the loop + activate_request_.erase(ctrl_it); + // reset chained mode request lists and will retry the creation of the request + clear_chained_mode_requests(); + return CreateRequestResult::RETRY; + } + if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) + { + RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! (::STRICT switch)"); + // reset all lists + clear_requests(); + return CreateRequestResult::ERROR; + } + } } - if (status != controller_interface::return_type::OK) + // check if controllers should be deactivated if used in chained mode + for (auto ctrl_it = deactivate_request_.begin(); ctrl_it != deactivate_request_.end(); + ++ctrl_it) { - RCLCPP_WARN( - get_logger(), - "Could not activate controller with name '%s'. Check above warnings for more details. " - "Check the state of the controllers and their required interfaces using " - "`ros2 control list_controllers -v` CLI to get more information.", - (*ctrl_it).c_str()); - if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT) + auto controller_it = std::find_if( + controllers.begin(), controllers.end(), + std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); + controller_interface::return_type status = controller_interface::return_type::OK; + + // if controller is not active then skip preceding-controllers checks + if (!is_controller_active(controller_it->c)) { - // TODO(destogl): automatic manipulation of the chain: - // || strictness == - // controller_manager_msgs::srv::SwitchController::Request::MANIPULATE_CONTROLLERS_CHAIN); - // remove controller that can not be activated from the activation request and step-back - // iterator to correctly step to the next element in the list in the loop - activate_request_.erase(ctrl_it); - --ctrl_it; + RCLCPP_WARN( + get_logger(), "Controller with name '%s' can not be deactivated since it is not active.", + controller_it->info.name.c_str()); + status = controller_interface::return_type::ERROR; } - if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) + else { - RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! (::STRICT switch)"); - // reset all lists - clear_requests(); - return controller_interface::return_type::ERROR; + status = + check_preceeding_controllers_for_deactivate(controllers, strictness, controller_it); + } + + if (status != controller_interface::return_type::OK) + { + RCLCPP_WARN( + get_logger(), + "Could not deactivate controller with name '%s'. Check above warnings for more details. " + "Check the state of the controllers and their required interfaces using " + "`ros2 control list_controllers -v` CLI to get more information.", + (*ctrl_it).c_str()); + if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT) + { + // remove controller that can not be activated from the activation request and step-back + // iterator to correctly step to the next element in the list in the loop + deactivate_request_.erase(ctrl_it); + // reset chained mode request lists and will retry the creation of the request + clear_chained_mode_requests(); + return CreateRequestResult::RETRY; + } + if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) + { + RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! (::STRICT switch)"); + // reset all lists + clear_requests(); + return CreateRequestResult::ERROR; + } } } - } - // check if controllers should be deactivated if used in chained mode - for (auto ctrl_it = deactivate_request_.begin(); ctrl_it != deactivate_request_.end(); ++ctrl_it) - { - auto controller_it = std::find_if( - controllers.begin(), controllers.end(), - std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it)); - controller_interface::return_type status = controller_interface::return_type::OK; + return CreateRequestResult::OK; + }; - // if controller is not active then skip preceding-controllers checks - if (!is_controller_active(controller_it->c)) + // Validate the (de)activate request and create from/to chained mode requests as needed. + // If the strictness value is STRICT, return an error for any invalid request. + // If the strictness value is BEST_EFFORT, remove any controllers that cannot be + // (de)activated from the request and proceed. However, any changes to the + // (de)activate request will affect the outcome of the check and creation process, + // so retry from the beginning. + while (true) + { + const auto result = check_de_activate_request_and_create_chained_mode_request(); + if (result == CreateRequestResult::RETRY) { - RCLCPP_WARN( - get_logger(), "Controller with name '%s' can not be deactivated since it is not active.", - controller_it->info.name.c_str()); - status = controller_interface::return_type::ERROR; + continue; } - else + if (result == CreateRequestResult::ERROR) { - status = check_preceeding_controllers_for_deactivate(controllers, strictness, controller_it); + return controller_interface::return_type::ERROR; } + // if result == CreateRequestResult::OK -> break the loop + break; + } - if (status != controller_interface::return_type::OK) - { - RCLCPP_WARN( - get_logger(), - "Could not deactivate controller with name '%s'. Check above warnings for more details. " - "Check the state of the controllers and their required interfaces using " - "`ros2 control list_controllers -v` CLI to get more information.", - (*ctrl_it).c_str()); - if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT) - { - // remove controller that can not be activated from the activation request and step-back - // iterator to correctly step to the next element in the list in the loop - deactivate_request_.erase(ctrl_it); - --ctrl_it; - } - if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT) - { - RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! (::STRICT switch)"); - // reset all lists - clear_requests(); - return controller_interface::return_type::ERROR; - } - } + // Check after the check if the activate and deactivate list is empty or not + if (activate_request_.empty() && deactivate_request_.empty()) + { + RCLCPP_INFO(get_logger(), "Empty activate and deactivate list, not requesting switch"); + clear_requests(); + return controller_interface::return_type::OK; } // Check after the check if the activate and deactivate list is empty or not diff --git a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp index 946ffbb4dc..6d3bde6c26 100644 --- a/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp +++ b/controller_manager/test/test_controllers_chaining_with_controller_manager.cpp @@ -46,6 +46,9 @@ class TestableTestChainableController : public test_chainable_controller::TestCh FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_activation_error_handling); + FRIEND_TEST( + TestControllerChainingWithControllerManager, + test_chained_controllers_activation_error_handling2); FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_activation_switching_error_handling); @@ -80,6 +83,9 @@ class TestableControllerManager : public controller_manager::ControllerManager FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_activation_error_handling); + FRIEND_TEST( + TestControllerChainingWithControllerManager, + test_chained_controllers_activation_error_handling2); FRIEND_TEST( TestControllerChainingWithControllerManager, test_chained_controllers_activation_switching_error_handling); @@ -1180,6 +1186,96 @@ TEST_P( ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, odom_publisher_controller->get_state().id()); + + // Check if the controllers are not in chained mode + ASSERT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + ASSERT_FALSE(sensor_fusion_controller->is_in_chained_mode()); +} + +TEST_P( + TestControllerChainingWithControllerManager, test_chained_controllers_activation_error_handling2) +{ + SetupControllers(); + + // add all controllers - CONTROLLERS HAVE TO ADDED IN EXECUTION ORDER + cm_->add_controller( + position_tracking_controller, POSITION_TRACKING_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + diff_drive_controller, DIFF_DRIVE_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + diff_drive_controller_two, DIFF_DRIVE_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + pid_left_wheel_controller, PID_LEFT_WHEEL, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + pid_right_wheel_controller, PID_RIGHT_WHEEL, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + odom_publisher_controller, ODOM_PUBLISHER_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + sensor_fusion_controller, SENSOR_FUSION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + robot_localization_controller, ROBOT_LOCALIZATION_CONTROLLER, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + cm_->add_controller( + position_tracking_controller_two, POSITION_TRACKING_CONTROLLER_TWO, + test_chainable_controller::TEST_CONTROLLER_CLASS_NAME); + + CheckIfControllersAreAddedCorrectly(); + + ConfigureAndCheckControllers(); + + // Set ControllerManager into Debug-Mode output to have detailed output on updating controllers + cm_->get_logger().set_level(rclcpp::Logger::Level::Debug); + rclcpp::get_logger("ControllerManager::utils").set_level(rclcpp::Logger::Level::Debug); + + // at beginning controllers are not in chained mode + EXPECT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); + EXPECT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); + + // Test Case: Trying to activate a preceding controller and one of the following controller + // --> return error; preceding controller are not activated, + // BUT following controller IS activated + static std::unordered_map expected = { + {controller_manager_msgs::srv::SwitchController::Request::STRICT, + {controller_interface::return_type::ERROR, std::future_status::ready, + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE}}, + {controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT, + {controller_interface::return_type::OK, std::future_status::timeout, + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE}}}; + + // Attempt to activate preceding controllers (position tracking and diff-drive controller) and + // one of the following controller (pid_left_wheel_controller) + switch_test_controllers( + {DIFF_DRIVE_CONTROLLER, PID_LEFT_WHEEL}, {}, test_param.strictness, + expected.at(test_param.strictness).future_status, + expected.at(test_param.strictness).return_type); + + // Preceding controller should stay deactivated and following controller + // should be activated (if BEST_EFFORT) + // If STRICT, preceding controller and following controller should stay deactivated + ASSERT_EQ(expected.at(test_param.strictness).state, pid_left_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + pid_right_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, + position_tracking_controller->get_state().id()); + + // Check if the controllers are not in chained mode + ASSERT_FALSE(pid_left_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(pid_right_wheel_controller->is_in_chained_mode()); + ASSERT_FALSE(diff_drive_controller->is_in_chained_mode()); } TEST_P( @@ -1533,6 +1629,42 @@ TEST_P( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_right_wheel_controller->get_state().id()); ASSERT_EQ( lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + + // Test Case: middle preceding/following controller deactivation but the most preceding and the + // lowest following controllers are active + // --> return error; controllers stay in the same state as they were + + // Activate all controllers for this test + ActivateController( + POSITION_TRACKING_CONTROLLER, controller_interface::return_type::OK, + std::future_status::timeout); + + // Expect all controllers to be active + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_left_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_right_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + position_tracking_controller->get_state().id()); + + // Attempt to deactivate the middle preceding/following controller + switch_test_controllers( + {}, {DIFF_DRIVE_CONTROLLER}, test_param.strictness, std::future_status::ready, + expected.at(test_param.strictness).return_type); + + // All controllers should still be active + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_left_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, pid_right_wheel_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, diff_drive_controller->get_state().id()); + ASSERT_EQ( + lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, + position_tracking_controller->get_state().id()); } TEST_P(