1818#include < vector>
1919
2020#include " controller_manager/controller_manager.hpp"
21+ #include " controller_manager_msgs/msg/controller_manager_activity.hpp"
2122#include " controller_manager_test_common.hpp"
2223#include " lifecycle_msgs/msg/state.hpp"
24+ #include " rclcpp/executor.hpp"
2325#include " test_chainable_controller/test_chainable_controller.hpp"
2426#include " test_controller/test_controller.hpp"
2527
@@ -30,6 +32,46 @@ class TestControllerManagerWithStrictness
3032: public ControllerManagerFixture<controller_manager::ControllerManager>,
3133 public testing::WithParamInterface<Strictness>
3234{
35+ public:
36+ void get_cm_status_message (
37+ const std::string & topic, controller_manager_msgs::msg::ControllerManagerActivity & cm_msg)
38+ {
39+ controller_manager_msgs::msg::ControllerManagerActivity::SharedPtr received_msg;
40+ rclcpp::Node test_node (" test_node" );
41+ auto subs_callback =
42+ [&](const controller_manager_msgs::msg::ControllerManagerActivity::SharedPtr msg)
43+ { received_msg = msg; };
44+ auto subscription =
45+ test_node.create_subscription <controller_manager_msgs::msg::ControllerManagerActivity>(
46+ topic, rclcpp::QoS (1 ).reliable ().transient_local (), subs_callback);
47+
48+ rclcpp::executors::SingleThreadedExecutor executor;
49+ executor.add_node (test_node.get_node_base_interface ());
50+ std::this_thread::sleep_for (std::chrono::milliseconds (200 ));
51+
52+ // call update to publish the test value
53+ // since update doesn't guarantee a published message, republish until received
54+ int max_sub_check_loop_count = 5 ; // max number of tries for pub/sub loop
55+ while (max_sub_check_loop_count--)
56+ {
57+ const auto timeout = std::chrono::milliseconds{50 };
58+ const auto until = test_node.get_clock ()->now () + timeout;
59+ while (!received_msg && test_node.get_clock ()->now () < until)
60+ {
61+ executor.spin_some ();
62+ std::this_thread::sleep_for (std::chrono::microseconds (10 ));
63+ }
64+ // check if message has been received
65+ if (received_msg.get ())
66+ {
67+ break ;
68+ }
69+ }
70+ ASSERT_GE (max_sub_check_loop_count, 0 ) << " Test was unable to publish a message through "
71+ " controller manager activity" ;
72+ ASSERT_TRUE (received_msg);
73+ cm_msg = *received_msg;
74+ }
3375};
3476
3577class TestControllerManagerRobotDescription
@@ -65,6 +107,15 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
65107 const auto test_param = GetParam ();
66108 auto test_controller = std::make_shared<test_controller::TestController>();
67109 auto test_controller2 = std::make_shared<test_controller::TestController>();
110+
111+ // Check for the hardware component and no controllers
112+ controller_manager_msgs::msg::ControllerManagerActivity cm_msg;
113+ const std::string cm_activity_topic =
114+ std::string (" /" ) + std::string (TEST_CM_NAME) + std::string (" /activity" );
115+ get_cm_status_message (cm_activity_topic, cm_msg);
116+ ASSERT_EQ (cm_msg.hardware_components .size (), 3u );
117+ ASSERT_EQ (cm_msg.controllers .size (), 0u );
118+
68119 constexpr char TEST_CONTROLLER2_NAME[] = " test_controller2_name" ;
69120 cm_->add_controller (
70121 test_controller, test_controller::TEST_CONTROLLER_NAME,
@@ -74,6 +125,14 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
74125 EXPECT_EQ (2u , cm_->get_loaded_controllers ().size ());
75126 EXPECT_EQ (2 , test_controller.use_count ());
76127
128+ get_cm_status_message (cm_activity_topic, cm_msg);
129+ ASSERT_EQ (cm_msg.hardware_components .size (), 3u );
130+ ASSERT_EQ (cm_msg.controllers .size (), 2u );
131+ ASSERT_EQ (cm_msg.controllers [0 ].name , test_controller::TEST_CONTROLLER_NAME);
132+ ASSERT_EQ (cm_msg.controllers [0 ].state .id , lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED);
133+ ASSERT_EQ (cm_msg.controllers [1 ].name , TEST_CONTROLLER2_NAME);
134+ ASSERT_EQ (cm_msg.controllers [1 ].state .id , lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED);
135+
77136 // setup interface to claim from controllers
78137 controller_interface::InterfaceConfiguration cmd_itfs_cfg;
79138 cmd_itfs_cfg.type = controller_interface::interface_configuration_type::INDIVIDUAL;
@@ -137,6 +196,14 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
137196 cm_->configure_controller (test_controller::TEST_CONTROLLER_NAME);
138197 cm_->configure_controller (TEST_CONTROLLER2_NAME);
139198 }
199+ get_cm_status_message (cm_activity_topic, cm_msg);
200+ ASSERT_EQ (cm_msg.hardware_components .size (), 3u );
201+ ASSERT_EQ (cm_msg.controllers .size (), 2u );
202+ ASSERT_EQ (cm_msg.controllers [0 ].name , TEST_CONTROLLER2_NAME);
203+ ASSERT_EQ (cm_msg.controllers [0 ].state .id , lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
204+ ASSERT_EQ (cm_msg.controllers [1 ].name , test_controller::TEST_CONTROLLER_NAME);
205+ ASSERT_EQ (cm_msg.controllers [1 ].state .id , lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
206+
140207 EXPECT_EQ (
141208 controller_interface::return_type::OK,
142209 cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
@@ -162,6 +229,16 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
162229 ControllerManagerRunner cm_runner (this );
163230 EXPECT_EQ (test_param.expected_return , switch_future.get ());
164231 }
232+ auto expected_ctrl2_state = test_param.strictness == 1
233+ ? lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE
234+ : lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE;
235+ get_cm_status_message (cm_activity_topic, cm_msg);
236+ ASSERT_EQ (cm_msg.hardware_components .size (), 3u );
237+ ASSERT_EQ (cm_msg.controllers .size (), 2u );
238+ ASSERT_EQ (cm_msg.controllers [0 ].name , TEST_CONTROLLER2_NAME);
239+ ASSERT_EQ (cm_msg.controllers [0 ].state .id , expected_ctrl2_state);
240+ ASSERT_EQ (cm_msg.controllers [1 ].name , test_controller::TEST_CONTROLLER_NAME);
241+ ASSERT_EQ (cm_msg.controllers [1 ].state .id , lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
165242
166243 EXPECT_EQ (
167244 controller_interface::return_type::OK,
@@ -189,6 +266,14 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
189266 EXPECT_EQ (
190267 lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, test_controller->get_lifecycle_state ().id ());
191268
269+ get_cm_status_message (cm_activity_topic, cm_msg);
270+ ASSERT_EQ (cm_msg.hardware_components .size (), 3u );
271+ ASSERT_EQ (cm_msg.controllers .size (), 2u );
272+ ASSERT_EQ (cm_msg.controllers [0 ].name , TEST_CONTROLLER2_NAME);
273+ ASSERT_EQ (cm_msg.controllers [0 ].state .id , expected_ctrl2_state);
274+ ASSERT_EQ (cm_msg.controllers [1 ].name , test_controller::TEST_CONTROLLER_NAME);
275+ ASSERT_EQ (cm_msg.controllers [1 ].state .id , lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
276+
192277 EXPECT_EQ (
193278 controller_interface::return_type::OK,
194279 cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
@@ -205,6 +290,14 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
205290 ASSERT_EQ (std::future_status::timeout, switch_future.wait_for (std::chrono::milliseconds (100 )))
206291 << " switch_controller should be blocking until next update cycle" ;
207292
293+ get_cm_status_message (cm_activity_topic, cm_msg);
294+ ASSERT_EQ (cm_msg.hardware_components .size (), 3u );
295+ ASSERT_EQ (cm_msg.controllers .size (), 2u );
296+ ASSERT_EQ (cm_msg.controllers [0 ].name , TEST_CONTROLLER2_NAME);
297+ ASSERT_EQ (cm_msg.controllers [0 ].state .id , expected_ctrl2_state);
298+ ASSERT_EQ (cm_msg.controllers [1 ].name , test_controller::TEST_CONTROLLER_NAME);
299+ ASSERT_EQ (cm_msg.controllers [1 ].state .id , lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
300+
208301 EXPECT_EQ (
209302 controller_interface::return_type::OK,
210303 cm_->update (time_, rclcpp::Duration::from_seconds (0.01 )));
@@ -227,6 +320,12 @@ TEST_P(TestControllerManagerWithStrictness, controller_lifecycle)
227320 ControllerManagerRunner cm_runner (this );
228321 EXPECT_EQ (controller_interface::return_type::OK, unload_future.get ());
229322
323+ get_cm_status_message (cm_activity_topic, cm_msg);
324+ ASSERT_EQ (cm_msg.hardware_components .size (), 3u );
325+ ASSERT_EQ (cm_msg.controllers .size (), 1u );
326+ ASSERT_EQ (cm_msg.controllers [0 ].name , TEST_CONTROLLER2_NAME);
327+ ASSERT_EQ (cm_msg.controllers [0 ].state .id , expected_ctrl2_state);
328+
230329 EXPECT_EQ (
231330 lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED,
232331 test_controller->get_lifecycle_state ().id ());
0 commit comments