6 #include <diagnostic_msgs/DiagnosticArray.h> 8 #include <fmt/format.h> 18 std::string memoryToString(uint64_t memory)
20 if(memory < static_cast<uint64_t>(1<<10))
21 return fmt::format(
"{} B", memory);
22 else if(memory < static_cast<uint64_t>(1<<20))
23 return fmt::format(
"{:.2f} KiB", static_cast<double>(memory) / static_cast<uint64_t>(1<<10));
24 else if(memory < static_cast<uint64_t>(1<<30))
25 return fmt::format(
"{:.2f} MiB", static_cast<double>(memory) / static_cast<uint64_t>(1<<20));
26 else if(memory < static_cast<uint64_t>(1ull<<40))
27 return fmt::format(
"{:.2f} GiB", static_cast<double>(memory) / static_cast<uint64_t>(1ull<<30));
29 return fmt::format(
"{:.2f} TiB", static_cast<double>(memory) / static_cast<uint64_t>(1ull<<40));
38 : m_diagnosticNamePrefix(diagnosticsPrefix)
41 if(diagnosticsPrefix.empty())
45 nh.
advertise<diagnostic_msgs::DiagnosticArray>(
"/diagnostics", 1,
true);
50 diagnostic_msgs::DiagnosticArray currentDiagnosticArray;
54 currentDiagnosticArray.status.reserve(state.size());
57 for(
const auto& nodeState : state)
59 diagnostic_msgs::DiagnosticStatus nodeStatus;
61 diagnostic_msgs::KeyValue kv;
63 kv.value = fmt::format(
"{:.1f}%",
64 (nodeState->userLoad() + nodeState->systemLoad()) * 100.);
65 nodeStatus.values.push_back(kv);
67 kv.key =
"used memory";
68 kv.value = memoryToString(nodeState->memory());
69 nodeStatus.values.push_back(kv);
76 nodeStatus.level = diagnostic_msgs::DiagnosticStatus::OK;
77 if(nodeState->state() == NodeMonitor::STATE_CRASHED)
79 nodeStatus.level = diagnostic_msgs::DiagnosticStatus::ERROR;
80 nodeStatus.message =
"Process has crashed";
84 if(nodeState->restartCount() > 0)
86 nodeStatus.level = diagnostic_msgs::DiagnosticStatus::WARN;
87 msg =
"restart count > 0!";
90 if(nodeState->memory() > nodeState->memoryLimit())
92 nodeStatus.level = diagnostic_msgs::DiagnosticStatus::WARN;
93 msg +=
"memory usage is high! ";
96 if(nodeState->userLoad() + nodeState->systemLoad() > nodeState->cpuLimit())
98 nodeStatus.level = diagnostic_msgs::DiagnosticStatus::WARN;
99 msg +=
"CPU load is high! ";
102 nodeStatus.message = msg;
105 currentDiagnosticArray.status.push_back(nodeStatus);
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL const std::string & getName()
ros::Publisher m_diagnosticsPublisher
std::string m_diagnosticNamePrefix
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
DiagnosticsPublisher(const std::string &diagnosticsPrefix)
void publish(const std::vector< rosmon::monitor::NodeMonitor::Ptr > &state)