diagnostics_publisher.cpp
Go to the documentation of this file.
1 // Publishes diagnostic_msgs/DiagnosticArray
2 // Authors: Adrien Barral, Max Schwarz
3 
5 
6 #include <diagnostic_msgs/DiagnosticArray.h>
7 
8 #include <fmt/format.h>
9 
10 #include <ros/node_handle.h>
11 #include <ros/this_node.h>
12 
13 using namespace rosmon::monitor;
14 
15 namespace
16 {
17 
18 std::string memoryToString(uint64_t memory)
19 {
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));
28  else
29  return fmt::format("{:.2f} TiB", static_cast<double>(memory) / static_cast<uint64_t>(1ull<<40));
30 }
31 
32 }
33 
34 namespace rosmon
35 {
36 
37 DiagnosticsPublisher::DiagnosticsPublisher(const std::string& diagnosticsPrefix)
38  : m_diagnosticNamePrefix(diagnosticsPrefix)
39 {
40  ros::NodeHandle nh;
41  if(diagnosticsPrefix.empty())
43 
45  nh.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1, true);
46 }
47 
48 void DiagnosticsPublisher::publish(const std::vector<NodeMonitor::Ptr>& state)
49 {
50  diagnostic_msgs::DiagnosticArray currentDiagnosticArray;
51 
52  // cleanup the diagnostic array result
53  currentDiagnosticArray.header.stamp = ros::Time::now();
54  currentDiagnosticArray.status.reserve(state.size());
55 
56  // convert state to diag :
57  for(const auto& nodeState : state)
58  {
59  diagnostic_msgs::DiagnosticStatus nodeStatus;
60  nodeStatus.name = m_diagnosticNamePrefix + nodeState->name();
61  diagnostic_msgs::KeyValue kv;
62  kv.key = "CPU Load";
63  kv.value = fmt::format("{:.1f}%",
64  (nodeState->userLoad() + nodeState->systemLoad()) * 100.);
65  nodeStatus.values.push_back(kv);
66 
67  kv.key = "used memory";
68  kv.value = memoryToString(nodeState->memory());
69  nodeStatus.values.push_back(kv);
70 
71  // Apply the operation level rule :
72  // If process is CRASHED => ERROR
73  // If process has been automatically restarted => WARN
74  // If process memory limit or cpu limit is too high => WARN
75  std::string msg;
76  nodeStatus.level = diagnostic_msgs::DiagnosticStatus::OK;
77  if(nodeState->state() == NodeMonitor::STATE_CRASHED)
78  {
79  nodeStatus.level = diagnostic_msgs::DiagnosticStatus::ERROR;
80  nodeStatus.message = "Process has crashed";
81  }
82  else
83  {
84  if(nodeState->restartCount() > 0)
85  {
86  nodeStatus.level = diagnostic_msgs::DiagnosticStatus::WARN;
87  msg = "restart count > 0!";
88  }
89 
90  if(nodeState->memory() > nodeState->memoryLimit())
91  {
92  nodeStatus.level = diagnostic_msgs::DiagnosticStatus::WARN;
93  msg += "memory usage is high! ";
94  }
95 
96  if(nodeState->userLoad() + nodeState->systemLoad() > nodeState->cpuLimit())
97  {
98  nodeStatus.level = diagnostic_msgs::DiagnosticStatus::WARN;
99  msg += "CPU load is high! ";
100  }
101 
102  nodeStatus.message = msg;
103  }
104 
105  currentDiagnosticArray.status.push_back(nodeStatus);
106  }
107 
108  m_diagnosticsPublisher.publish(currentDiagnosticArray);
109 }
110 
111 }
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL const std::string & getName()
state
Definition: basic.py:139
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
DiagnosticsPublisher(const std::string &diagnosticsPrefix)
static Time now()
void publish(const std::vector< rosmon::monitor::NodeMonitor::Ptr > &state)


rosmon_core
Author(s): Max Schwarz
autogenerated on Wed Jul 10 2019 03:10:12