Skip to content

Commit

Permalink
Add diagnostics (backport #820) (#922)
Browse files Browse the repository at this point in the history
* Add diagnostics for controllers activity (#820)

(cherry picked from commit b1f31a1)

Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: Bence Magyar <[email protected]>
  • Loading branch information
3 people authored Jan 24, 2023
1 parent 9dcda34 commit dca10f4
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 2 deletions.
1 change: 1 addition & 0 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
ament_index_cpp
controller_interface
controller_manager_msgs
diagnostic_updater
hardware_interface
pluginlib
rclcpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include "controller_manager_msgs/srv/switch_controller.hpp"
#include "controller_manager_msgs/srv/unload_controller.hpp"

#include "diagnostic_updater/diagnostic_updater.hpp"
#include "hardware_interface/handle.hpp"
#include "hardware_interface/resource_manager.hpp"

Expand Down Expand Up @@ -345,6 +346,9 @@ class ControllerManager : public rclcpp::Node
const std::vector<ControllerSpec> & controllers, int strictness,
const ControllersListIterator controller_it);

void controller_activity_diagnostic_callback(diagnostic_updater::DiagnosticStatusWrapper & stat);
diagnostic_updater::Updater diagnostics_updater_;

std::shared_ptr<rclcpp::Executor> executor_;

std::shared_ptr<pluginlib::ClassLoader<controller_interface::ControllerInterface>> loader_;
Expand Down
1 change: 1 addition & 0 deletions controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<depend>backward_ros</depend>
<depend>controller_interface</depend>
<depend>controller_manager_msgs</depend>
<depend>diagnostic_updater</depend>
<depend>hardware_interface</depend>
<depend>launch</depend>
<depend>launch_ros</depend>
Expand Down
38 changes: 36 additions & 2 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,8 @@ ControllerManager::ControllerManager(
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
chainable_loader_(
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName)),
diagnostics_updater_(this)
{
if (!get_parameter("update_rate", update_rate_))
{
Expand All @@ -163,6 +164,9 @@ ControllerManager::ControllerManager(

init_resource_manager(robot_description);

diagnostics_updater_.setHardwareID("ros2_control");
diagnostics_updater_.add(
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);
init_services();
}

Expand All @@ -177,12 +181,16 @@ ControllerManager::ControllerManager(
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
chainable_loader_(
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName)),
diagnostics_updater_(this)
{
if (!get_parameter("update_rate", update_rate_))
{
RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value.");
}
diagnostics_updater_.setHardwareID("ros2_control");
diagnostics_updater_.add(
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);
init_services();
}

Expand Down Expand Up @@ -2043,4 +2051,30 @@ controller_interface::return_type ControllerManager::check_preceeding_controller
return controller_interface::return_type::OK;
};

void ControllerManager::controller_activity_diagnostic_callback(
diagnostic_updater::DiagnosticStatusWrapper & stat)
{
// lock controllers
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
const std::vector<ControllerSpec> & controllers = rt_controllers_wrapper_.get_updated_list(guard);
bool all_active = true;
for (size_t i = 0; i < controllers.size(); ++i)
{
if (!is_controller_active(controllers[i].c))
{
all_active = false;
}
stat.add(controllers[i].info.name, controllers[i].c->get_state().label());
}

if (all_active)
{
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "All controllers are active");
}
else
{
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Not all controllers are active");
}
}

} // namespace controller_manager

0 comments on commit dca10f4

Please sign in to comment.