3232#include " rclcpp/utilities.hpp"
3333
3434#include " ros2_control_test_assets/descriptions.hpp"
35- #include " test_controller/test_controller.hpp"
3635#include " test_controller_failed_init/test_controller_failed_init.hpp"
3736
3837constexpr auto STRICT = controller_manager_msgs::srv::SwitchController::Request::STRICT;
3938constexpr auto BEST_EFFORT = controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT;
4039
4140const auto TEST_CM_NAME = " test_controller_manager" ;
4241
42+ // Strictness structure for parameterized tests - shared between different tests
43+ struct Strictness
44+ {
45+ int strictness = STRICT;
46+ controller_interface::return_type expected_return;
47+ unsigned int expected_counter;
48+ };
49+ Strictness strict{STRICT, controller_interface::return_type::ERROR, 0u };
50+ Strictness best_effort{BEST_EFFORT, controller_interface::return_type::OK, 1u };
51+
52+ // Forward definition to avid compile error - defined at the end of the file
53+ template <typename CtrlMgr>
54+ class ControllerManagerRunner ;
55+
56+ template <typename CtrlMgr>
4357class ControllerManagerFixture : public ::testing::Test
4458{
4559public:
@@ -50,7 +64,7 @@ class ControllerManagerFixture : public ::testing::Test
5064 void SetUp ()
5165 {
5266 executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
53- cm_ = std::make_shared<controller_manager::ControllerManager >(
67+ cm_ = std::make_shared<CtrlMgr >(
5468 std::make_unique<hardware_interface::ResourceManager>(
5569 ros2_control_test_assets::minimal_robot_urdf, true , true ),
5670 executor_, TEST_CM_NAME);
@@ -80,14 +94,32 @@ class ControllerManagerFixture : public ::testing::Test
8094 }
8195 }
8296
97+ void switch_test_controllers (
98+ const std::vector<std::string> & start_controllers,
99+ const std::vector<std::string> & stop_controllers, const int strictness,
100+ const std::future_status expected_future_status = std::future_status::timeout,
101+ const controller_interface::return_type expected_return = controller_interface::return_type::OK)
102+ {
103+ // First activation not possible because controller not configured
104+ auto switch_future = std::async (
105+ std::launch::async, &controller_manager::ControllerManager::switch_controller, cm_,
106+ start_controllers, stop_controllers, strictness, true , rclcpp::Duration (0 , 0 ));
107+
108+ ASSERT_EQ (expected_future_status, switch_future.wait_for (std::chrono::milliseconds (100 )))
109+ << " switch_controller should be blocking until next update cycle" ;
110+ ControllerManagerRunner<CtrlMgr> cm_runner (this );
111+ EXPECT_EQ (expected_return, switch_future.get ());
112+ }
113+
83114 std::shared_ptr<rclcpp::Executor> executor_;
84- std::shared_ptr<controller_manager::ControllerManager > cm_;
115+ std::shared_ptr<CtrlMgr > cm_;
85116
86117 std::thread updater_;
87118 bool run_updater_;
88119};
89120
90- class TestControllerManagerSrvs : public ControllerManagerFixture
121+ class TestControllerManagerSrvs
122+ : public ControllerManagerFixture<controller_manager::ControllerManager>
91123{
92124public:
93125 TestControllerManagerSrvs () {}
@@ -146,17 +178,18 @@ class TestControllerManagerSrvs : public ControllerManagerFixture
146178 std::future<void > executor_spin_future_;
147179};
148180
181+ template <typename CtrlMgr>
149182class ControllerManagerRunner
150183{
151184public:
152- explicit ControllerManagerRunner (ControllerManagerFixture * cmf) : cmf_(cmf)
185+ explicit ControllerManagerRunner (ControllerManagerFixture<CtrlMgr> * cmf) : cmf_(cmf)
153186 {
154187 cmf_->startCmUpdater ();
155188 }
156189
157190 ~ControllerManagerRunner () { cmf_->stopCmUpdater (); }
158191
159- ControllerManagerFixture * cmf_;
192+ ControllerManagerFixture<CtrlMgr> * cmf_;
160193};
161194
162195class ControllerMock : public controller_interface ::ControllerInterface
0 commit comments