Skip to content

Commit 5c77293

Browse files
authored
Merge branch 'master' into add/statistics/hardware_components
2 parents e45355c + bfbedd2 commit 5c77293

File tree

12 files changed

+305
-19
lines changed

12 files changed

+305
-19
lines changed

controller_manager/doc/userdoc.rst

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,14 @@ Alternatives to the standard kernel include
4545
Though installing a realtime-kernel will definitely get the best results when it comes to low
4646
jitter, using a lowlatency kernel can improve things a lot with being really easy to install.
4747

48+
Publishers
49+
-----------
50+
51+
~/activity [controller_manager_msgs::msg::ControllerManagerActivity]
52+
A topic that is published every time there is a change of state of the controllers or hardware components managed by the controller manager.
53+
The message contains the list of the controllers and the hardware components that are managed by the controller manager along with their lifecycle states.
54+
The topic is published using the "transient local" quality of service, so subscribers should also be "transient local".
55+
4856
Subscribers
4957
-----------
5058

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
#include "controller_interface/controller_interface_base.hpp"
2828

2929
#include "controller_manager/controller_spec.hpp"
30+
#include "controller_manager_msgs/msg/controller_manager_activity.hpp"
3031
#include "controller_manager_msgs/srv/configure_controller.hpp"
3132
#include "controller_manager_msgs/srv/list_controller_types.hpp"
3233
#include "controller_manager_msgs/srv/list_controllers.hpp"
@@ -430,6 +431,13 @@ class ControllerManager : public rclcpp::Node
430431
const std::string & ctrl_name, std::vector<std::string>::iterator controller_iterator,
431432
bool append_to_controller);
432433

434+
/**
435+
* @brief Method to publish the state of the controller manager.
436+
* The state includes the list of controllers and the list of hardware interfaces along with
437+
* their states.
438+
*/
439+
void publish_activity();
440+
433441
void controller_activity_diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat);
434442

435443
void hardware_components_diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat);
@@ -521,6 +529,12 @@ class ControllerManager : public rclcpp::Node
521529
*/
522530
void switch_updated_list(const std::lock_guard<std::recursive_mutex> & guard);
523531

532+
/// A method to register a callback to be called when the list is switched
533+
/**
534+
* \param[in] callback Callback to be called when the list is switched
535+
*/
536+
void set_on_switch_callback(std::function<void()> callback);
537+
524538
// Mutex protecting the controllers list
525539
// must be acquired before using any list other than the "used by rt"
526540
mutable std::recursive_mutex controllers_lock_;
@@ -542,6 +556,8 @@ class ControllerManager : public rclcpp::Node
542556
int updated_controllers_index_ = 0;
543557
/// The index of the controllers list being used in the real-time thread.
544558
int used_by_realtime_controllers_index_ = -1;
559+
/// The callback to be called when the list is switched
560+
std::function<void()> on_switch_callback_ = nullptr;
545561
};
546562

547563
std::unique_ptr<rclcpp::PreShutdownCallbackHandle> preshutdown_cb_handle_{nullptr};
@@ -551,6 +567,8 @@ class ControllerManager : public rclcpp::Node
551567
/// mutex copied from ROS1 Control, protects service callbacks
552568
/// not needed if we're guaranteed that the callbacks don't come from multiple threads
553569
std::mutex services_lock_;
570+
rclcpp::Publisher<controller_manager_msgs::msg::ControllerManagerActivity>::SharedPtr
571+
controller_manager_activity_publisher_;
554572
rclcpp::Service<controller_manager_msgs::srv::ListControllers>::SharedPtr
555573
list_controllers_service_;
556574
rclcpp::Service<controller_manager_msgs::srv::ListControllerTypes>::SharedPtr

controller_manager/src/controller_manager.cpp

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -373,6 +373,14 @@ bool ControllerManager::shutdown_controllers()
373373

374374
void ControllerManager::init_controller_manager()
375375
{
376+
controller_manager_activity_publisher_ =
377+
create_publisher<controller_manager_msgs::msg::ControllerManagerActivity>(
378+
"~/activity", rclcpp::QoS(1).reliable().transient_local());
379+
rt_controllers_wrapper_.set_on_switch_callback(
380+
std::bind(&ControllerManager::publish_activity, this));
381+
resource_manager_->set_on_component_state_switch_callback(
382+
std::bind(&ControllerManager::publish_activity, this));
383+
376384
// Get parameters needed for RT "update" loop to work
377385
if (is_resource_manager_initialized())
378386
{
@@ -2695,6 +2703,8 @@ controller_interface::return_type ControllerManager::update(
26952703
{
26962704
activate_controllers(rt_controller_list, rt_buffer_.fallback_controllers_list);
26972705
}
2706+
// To publish the activity of the failing controllers and the fallback controllers
2707+
publish_activity();
26982708
}
26992709

27002710
// there are controllers to (de)activate
@@ -2784,6 +2794,17 @@ void ControllerManager::RTControllerListWrapper::switch_updated_list(
27842794
int former_current_controllers_list_ = updated_controllers_index_;
27852795
updated_controllers_index_ = get_other_list(former_current_controllers_list_);
27862796
wait_until_rt_not_using(former_current_controllers_list_);
2797+
if (on_switch_callback_)
2798+
{
2799+
on_switch_callback_();
2800+
}
2801+
}
2802+
2803+
void ControllerManager::RTControllerListWrapper::set_on_switch_callback(
2804+
std::function<void()> callback)
2805+
{
2806+
std::lock_guard<std::recursive_mutex> guard(controllers_lock_);
2807+
on_switch_callback_ = callback;
27872808
}
27882809

27892810
int ControllerManager::RTControllerListWrapper::get_other_list(int index) const
@@ -3231,6 +3252,38 @@ ControllerManager::check_fallback_controllers_state_pre_activation(
32313252
return controller_interface::return_type::OK;
32323253
}
32333254

3255+
void ControllerManager::publish_activity()
3256+
{
3257+
controller_manager_msgs::msg::ControllerManagerActivity status_msg;
3258+
status_msg.header.stamp = get_clock()->now();
3259+
{
3260+
// lock controllers
3261+
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
3262+
const std::vector<ControllerSpec> & controllers =
3263+
rt_controllers_wrapper_.get_updated_list(guard);
3264+
for (const auto & controller : controllers)
3265+
{
3266+
controller_manager_msgs::msg::NamedLifecycleState lifecycle_info;
3267+
lifecycle_info.name = controller.info.name;
3268+
lifecycle_info.state.id = controller.c->get_lifecycle_state().id();
3269+
lifecycle_info.state.label = controller.c->get_lifecycle_state().label();
3270+
status_msg.controllers.push_back(lifecycle_info);
3271+
}
3272+
}
3273+
{
3274+
const auto hw_components_info = resource_manager_->get_components_status();
3275+
for (const auto & [component_name, component_info] : hw_components_info)
3276+
{
3277+
controller_manager_msgs::msg::NamedLifecycleState lifecycle_info;
3278+
lifecycle_info.name = component_name;
3279+
lifecycle_info.state.id = component_info.state.id();
3280+
lifecycle_info.state.label = component_info.state.label();
3281+
status_msg.hardware_components.push_back(lifecycle_info);
3282+
}
3283+
}
3284+
controller_manager_activity_publisher_->publish(status_msg);
3285+
}
3286+
32343287
void ControllerManager::controller_activity_diagnostic_callback(
32353288
diagnostic_updater::DiagnosticStatusWrapper & stat)
32363289
{

controller_manager/test/test_controller_manager.cpp

Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,10 @@
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

3577
class 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());

controller_manager_msgs/CMakeLists.txt

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,16 @@ project(controller_manager_msgs)
44
find_package(ament_cmake REQUIRED)
55
find_package(builtin_interfaces REQUIRED)
66
find_package(lifecycle_msgs REQUIRED)
7+
find_package(std_msgs REQUIRED)
78
find_package(rosidl_default_generators REQUIRED)
89

910
set(msg_files
1011
msg/ControllerState.msg
1112
msg/ChainConnection.msg
1213
msg/HardwareComponentState.msg
1314
msg/HardwareInterface.msg
15+
msg/NamedLifecycleState.msg
16+
msg/ControllerManagerActivity.msg
1417
)
1518
set(srv_files
1619
srv/ConfigureController.srv
@@ -28,7 +31,7 @@ set(srv_files
2831
rosidl_generate_interfaces(${PROJECT_NAME}
2932
${msg_files}
3033
${srv_files}
31-
DEPENDENCIES builtin_interfaces lifecycle_msgs
34+
DEPENDENCIES builtin_interfaces lifecycle_msgs std_msgs
3235
ADD_LINTER_TESTS
3336
)
3437
ament_export_dependencies(rosidl_default_runtime)
Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
# This message is used to provide the activity within the controller manager regarding the change in state of controllers and hardware interfaces
2+
3+
# The header is used to provide timestamp information
4+
std_msgs/Header header
5+
6+
# The current state of the controllers
7+
NamedLifecycleState[] controllers
8+
9+
# The current state of the hardware components
10+
NamedLifecycleState[] hardware_components
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
# This message is used to provide information about the lifecycle state of the controller or the hardware components
2+
3+
# The name of the controller or hardware interface
4+
string name
5+
6+
# The current lifecycle state of the controller or hardware components
7+
lifecycle_msgs/State state

controller_manager_msgs/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,11 @@
1515

1616
<build_depend>builtin_interfaces</build_depend>
1717
<build_depend>lifecycle_msgs</build_depend>
18+
<build_depend>std_msgs</build_depend>
1819

1920
<exec_depend>builtin_interfaces</exec_depend>
2021
<exec_depend>lifecycle_msgs</exec_depend>
22+
<exec_depend>std_msgs</exec_depend>
2123
<exec_depend>rosidl_default_runtime</exec_depend>
2224

2325
<test_depend>ament_lint_common</test_depend>

doc/release_notes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -90,6 +90,7 @@ controller_manager
9090
* The ``cpu_affinity`` parameter can now accept of types ``int`` or ``int_array`` to bind the process to a specific CPU core or multiple CPU cores. (`#1915 <https://github.com/ros-controls/ros2_control/pull/1915>`_).
9191
* The ``pal_statistics`` is now integrated into the controller_manager, so that the controllers, hardware components and the controller_manager can be easily introspected and monitored using the topics ``~/introspection_data/names`` and ``~/introspection_data/values`` (`#1918 <https://github.com/ros-controls/ros2_control/pull/1918>`_).
9292
* A python module ``test_utils`` was added to the ``controller_manager`` package to help with integration testing (`#1955 <https://github.com/ros-controls/ros2_control/pull/1955>`_).
93+
* A latched topic ``~/activity`` has been added to the controller_manager to publish the activity of the controller_manager, where the change in states of the controllers and the hardware components are published. (`#2006 <https://github.com/ros-controls/ros2_control/pull/2006>`_).
9394

9495
hardware_interface
9596
******************

hardware_interface/include/hardware_interface/resource_manager.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -464,6 +464,12 @@ class ResourceManager
464464
*/
465465
bool state_interface_exists(const std::string & key) const;
466466

467+
/// A method to register a callback to be called when the component state changes.
468+
/**
469+
* \param[in] callback function to be called when the component state changes.
470+
*/
471+
void set_on_component_state_switch_callback(std::function<void()> callback);
472+
467473
protected:
468474
/// Gets the logger for the resource manager
469475
/**

0 commit comments

Comments
 (0)