@@ -2280,3 +2280,180 @@ TEST_F(
22802280 test_chainable_controller->get_lifecycle_state ().id ());
22812281 }
22822282}
2283+
2284+ TEST_F (
2285+ TestControllerManagerChainableControllerFailedActivation,
2286+ test_chainable_controllers_failed_activation_stops_all_list)
2287+ {
2288+ const std::string test_chainable_controller_2_name = " test_chainable_controller_2" ;
2289+
2290+ const auto strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
2291+ controller_interface::InterfaceConfiguration cmd_itfs_cfg;
2292+ controller_interface::InterfaceConfiguration itfs_cfg;
2293+ cmd_itfs_cfg.type = controller_interface::interface_configuration_type::INDIVIDUAL;
2294+ itfs_cfg.type = controller_interface::interface_configuration_type::INDIVIDUAL;
2295+
2296+ // controller 1
2297+ auto test_chainable_controller =
2298+ std::make_shared<test_chainable_controller::TestChainableController>();
2299+ cmd_itfs_cfg.names = {" joint1/position" };
2300+ itfs_cfg.names = {" joint2/velocity" };
2301+ test_chainable_controller->set_command_interface_configuration (cmd_itfs_cfg);
2302+ test_chainable_controller->set_state_interface_configuration (itfs_cfg);
2303+ test_chainable_controller->set_reference_interface_names ({" modified_joint1/position" });
2304+ test_chainable_controller->set_exported_state_interface_names ({" modified_joint2/velocity" });
2305+ test_chainable_controller->fail_on_activate = false ;
2306+
2307+ auto test_chainable_controller_2 =
2308+ std::make_shared<test_chainable_controller::TestChainableController>();
2309+ cmd_itfs_cfg.names = {" joint2/velocity" };
2310+ itfs_cfg.names = {" joint2/velocity" };
2311+ test_chainable_controller_2->set_command_interface_configuration (cmd_itfs_cfg);
2312+ test_chainable_controller_2->set_state_interface_configuration (itfs_cfg);
2313+ test_chainable_controller_2->set_reference_interface_names ({" modified_joint2/position" });
2314+ test_chainable_controller_2->set_exported_state_interface_names ({" modified_joint2/velocity" });
2315+ test_chainable_controller_2->fail_on_activate = false ;
2316+
2317+ auto test_controller = std::make_shared<test_controller::TestController>();
2318+ cmd_itfs_cfg.names = {
2319+ std::string (test_chainable_controller::TEST_CONTROLLER_NAME) + " /modified_joint1/position" };
2320+ test_controller->set_command_interface_configuration (cmd_itfs_cfg);
2321+ test_controller->set_state_interface_configuration (itfs_cfg);
2322+
2323+ cm_->add_controller (
2324+ test_chainable_controller, test_chainable_controller::TEST_CONTROLLER_NAME,
2325+ test_chainable_controller::TEST_CONTROLLER_CLASS_NAME);
2326+ cm_->add_controller (
2327+ test_chainable_controller_2, test_chainable_controller_2_name,
2328+ test_chainable_controller::TEST_CONTROLLER_CLASS_NAME);
2329+ cm_->add_controller (
2330+ test_controller, test_controller::TEST_CONTROLLER_NAME,
2331+ test_controller::TEST_CONTROLLER_CLASS_NAME);
2332+
2333+ EXPECT_EQ (3u , cm_->get_loaded_controllers ().size ());
2334+ EXPECT_EQ (2 , test_chainable_controller.use_count ());
2335+ EXPECT_EQ (2 , test_chainable_controller_2.use_count ());
2336+ EXPECT_EQ (2 , test_controller.use_count ());
2337+ EXPECT_EQ (
2338+ controller_interface::return_type::OK,
2339+ cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
2340+
2341+ EXPECT_EQ (
2342+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2343+ test_chainable_controller->get_lifecycle_state ().id ());
2344+ EXPECT_EQ (
2345+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2346+ test_chainable_controller_2->get_lifecycle_state ().id ());
2347+ EXPECT_EQ (
2348+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2349+ test_controller->get_lifecycle_state ().id ());
2350+
2351+ // configure controllers
2352+ {
2353+ ControllerManagerRunner cm_runner (this );
2354+ EXPECT_EQ (
2355+ controller_interface::return_type::OK,
2356+ cm_->configure_controller (test_chainable_controller::TEST_CONTROLLER_NAME));
2357+ EXPECT_EQ (
2358+ controller_interface::return_type::OK,
2359+ cm_->configure_controller (test_chainable_controller_2_name));
2360+ EXPECT_EQ (
2361+ controller_interface::return_type::OK,
2362+ cm_->configure_controller (test_controller::TEST_CONTROLLER_NAME));
2363+ }
2364+
2365+ std::vector<std::string> start_controllers = {
2366+ test_chainable_controller::TEST_CONTROLLER_NAME, test_chainable_controller_2_name,
2367+ test_controller::TEST_CONTROLLER_NAME};
2368+ std::vector<std::string> stop_controllers = {};
2369+ {
2370+ ControllerManagerRunner cm_runner (this );
2371+
2372+ auto switch_future = std::async (
2373+ std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
2374+ start_controllers, stop_controllers, strictness, true , rclcpp::Duration (0 , 0 ));
2375+ ASSERT_EQ (std::future_status::ready, switch_future.wait_for (std::chrono::milliseconds (100 )))
2376+ << " switch_controller should be blocking until next update cycle" ;
2377+ EXPECT_EQ (controller_interface::return_type::OK, switch_future.get ());
2378+ EXPECT_EQ (
2379+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
2380+ test_chainable_controller->get_lifecycle_state ().id ());
2381+ EXPECT_EQ (
2382+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
2383+ test_chainable_controller_2->get_lifecycle_state ().id ());
2384+ EXPECT_EQ (
2385+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
2386+ test_controller->get_lifecycle_state ().id ());
2387+
2388+ // Now deactivate all the controllers
2389+ auto switch_future_2 = std::async (
2390+ std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
2391+ stop_controllers, start_controllers, strictness, true , rclcpp::Duration (0 , 0 ));
2392+ ASSERT_EQ (std::future_status::ready, switch_future_2.wait_for (std::chrono::milliseconds (100 )))
2393+ << " switch_controller should be blocking until next update cycle" ;
2394+ EXPECT_EQ (controller_interface::return_type::OK, switch_future_2.get ());
2395+ EXPECT_EQ (
2396+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2397+ test_chainable_controller->get_lifecycle_state ().id ());
2398+ EXPECT_EQ (
2399+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2400+ test_chainable_controller_2->get_lifecycle_state ().id ());
2401+ EXPECT_EQ (
2402+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2403+ test_controller->get_lifecycle_state ().id ());
2404+ }
2405+
2406+ // Now, let's make the first controller fail on activation and see that all the controllers are
2407+ // set to inactive in strict mode
2408+ test_chainable_controller->fail_on_activate = true ;
2409+ {
2410+ ControllerManagerRunner cm_runner (this );
2411+
2412+ auto switch_future = std::async (
2413+ std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
2414+ start_controllers, stop_controllers, strictness, true , rclcpp::Duration (0 , 0 ));
2415+ ASSERT_EQ (std::future_status::ready, switch_future.wait_for (std::chrono::milliseconds (100 )))
2416+ << " switch_controller should be blocking until next update cycle" ;
2417+ EXPECT_EQ (controller_interface::return_type::ERROR, switch_future.get ());
2418+ EXPECT_EQ (
2419+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2420+ test_chainable_controller->get_lifecycle_state ().id ());
2421+ EXPECT_EQ (
2422+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2423+ test_chainable_controller_2->get_lifecycle_state ().id ());
2424+ EXPECT_EQ (
2425+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2426+ test_controller->get_lifecycle_state ().id ());
2427+ }
2428+
2429+ // Now, reconfigure and test with BEST_EFFORT strictness and see that the other two controllers
2430+ // are active
2431+ {
2432+ ControllerManagerRunner cm_runner (this );
2433+ EXPECT_EQ (
2434+ controller_interface::return_type::OK,
2435+ cm_->configure_controller (test_chainable_controller::TEST_CONTROLLER_NAME));
2436+ EXPECT_EQ (
2437+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2438+ test_chainable_controller->get_lifecycle_state ().id ());
2439+
2440+ const auto best_effort_strictness =
2441+ controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT;
2442+ auto switch_future = std::async (
2443+ std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
2444+ start_controllers, stop_controllers, best_effort_strictness, true , rclcpp::Duration (0 , 0 ));
2445+ ASSERT_EQ (std::future_status::ready, switch_future.wait_for (std::chrono::milliseconds (100 )))
2446+ << " switch_controller should be blocking until next update cycle" ;
2447+ EXPECT_EQ (controller_interface::return_type::ERROR, switch_future.get ());
2448+ EXPECT_EQ (
2449+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
2450+ test_chainable_controller->get_lifecycle_state ().id ());
2451+ EXPECT_EQ (
2452+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE,
2453+ test_chainable_controller_2->get_lifecycle_state ().id ());
2454+ // test controller needs to be inactive as it depends on the failed controller's interface
2455+ EXPECT_EQ (
2456+ lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE,
2457+ test_controller->get_lifecycle_state ().id ());
2458+ }
2459+ }
0 commit comments