Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add diagnostics #2986

Merged
merged 3 commits into from
Jun 1, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions nav2_lifecycle_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ find_package(std_msgs REQUIRED)
find_package(std_srvs REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(bondcpp REQUIRED)
find_package(diagnostic_updater REQUIRED)

nav2_package()

Expand Down Expand Up @@ -42,6 +43,7 @@ set(dependencies
std_srvs
tf2_geometry_msgs
bondcpp
diagnostic_updater
)

ament_target_dependencies(${library_name}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
#include "nav2_msgs/srv/manage_lifecycle_nodes.hpp"
#include "std_srvs/srv/trigger.hpp"
#include "bondcpp/bond.hpp"
#include "diagnostic_updater/diagnostic_updater.hpp"


namespace nav2_lifecycle_manager
{
Expand Down Expand Up @@ -178,6 +180,12 @@ class LifecycleManager : public rclcpp::Node
*/
void message(const std::string & msg);

// Diagnostics functions
/**
* @brief function to check if the Nav2 system is active
*/
void CreateActiveDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat);

// Timer thread to look at bond connections
rclcpp::TimerBase::SharedPtr init_timer_;
rclcpp::TimerBase::SharedPtr bond_timer_;
Expand All @@ -203,6 +211,7 @@ class LifecycleManager : public rclcpp::Node
bool attempt_respawn_reconnection_;

bool system_active_{false};
diagnostic_updater::Updater diagnostics_updater_;

rclcpp::Time bond_respawn_start_time_{0};
rclcpp::Duration bond_respawn_max_duration_{10s};
Expand Down
2 changes: 2 additions & 0 deletions nav2_lifecycle_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<build_depend>tf2_geometry_msgs</build_depend>
<build_depend>bondcpp</build_depend>
<build_depend>nav2_common</build_depend>
<build_depend>diagnostic_updater</build_depend>

<exec_depend>geometry_msgs</exec_depend>
<exec_depend>lifecycle_msgs</exec_depend>
Expand All @@ -31,6 +32,7 @@
<exec_depend>std_srvs</exec_depend>
<exec_depend>bondcpp</exec_depend>
<exec_depend>tf2_geometry_msgs</exec_depend>
<exec_depend>diagnostic_updater</exec_depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
14 changes: 13 additions & 1 deletion nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ namespace nav2_lifecycle_manager
{

LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options)
: Node("lifecycle_manager", options)
: Node("lifecycle_manager", options), diagnostics_updater_(this)
{
RCLCPP_INFO(get_logger(), "Creating");

Expand Down Expand Up @@ -103,6 +103,8 @@ LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options)
executor->add_callback_group(callback_group_, get_node_base_interface());
service_thread_ = std::make_unique<nav2_util::NodeThread>(executor);
});
diagnostics_updater_.setHardwareID("Nav2");
diagnostics_updater_.add("Nav2 Health", this, &LifecycleManager::CreateActiveDiagnostic);
}

LifecycleManager::~LifecycleManager()
Expand Down Expand Up @@ -145,6 +147,16 @@ LifecycleManager::isActiveCallback(
response->success = system_active_;
}

void
LifecycleManager::CreateActiveDiagnostic(diagnostic_updater::DiagnosticStatusWrapper & stat)
{
if (system_active_) {
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Nav2 is active");
} else {
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::ERROR, "Nav2 is inactive");
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
}
}

void
LifecycleManager::createLifecycleServiceClients()
{
Expand Down