20 #ifndef CPU_MEM_MONITOR_CPU_MEM_MONITOR_H_
21 #define CPU_MEM_MONITOR_CPU_MEM_MONITOR_H_
23 #include <pluginlib/class_list_macros.h>
26 #include <ros/package.h>
34 #include <sys/types.h>
35 #include <sys/sysinfo.h>
36 #include <shared_mutex>
40 #include <ff_msgs/CpuState.h>
41 #include <ff_msgs/CpuStateStamped.h>
42 #include <ff_msgs/MemState.h>
43 #include <ff_msgs/MemStateStamped.h>
81 void AssertCPULoadHighFaultCallback(ros::TimerEvent
const& te);
82 void ClearCPULoadHighFaultCallback(ros::TimerEvent
const& te);
85 void AssertMemLoadHighFaultCallback(ros::TimerEvent
const& te);
86 void ClearMemLoadHighFaultCallback(ros::TimerEvent
const& te);
89 void AssertCpuStats();
90 void AssertMemStats();
95 int CollectCPUStats();
96 int CollectMemStats();
99 void PublishStatsCallback(ros::TimerEvent
const &te);
103 std::uint64_t total_time,
116 double total_percentage,
123 std::shared_timed_mutex pid_lock_;
126 ros::Publisher cpu_state_pub_;
127 ros::Publisher mem_state_pub_;
128 ros::Timer reload_params_timer_;
129 ros::Timer stats_timer_;
130 ros::Timer assert_cpu_load_fault_timer_;
131 ros::Timer clear_cpu_load_fault_timer_;
132 ros::Timer assert_mem_load_fault_timer_;
133 ros::Timer clear_mem_load_fault_timer_;
135 double update_freq_hz_;
136 struct sysinfo mem_info_;
139 std::string processor_name_;
141 std::string monitor_host_;
143 std::map<std::string, int> nodes_pid_;
144 std::map<std::string, uint64_t> nodes_proc_time_;
147 bool temp_fault_triggered_;
149 double temperature_scale_;
150 float avg_cpu_load_high_value_;
151 std::vector<Load> load_cpus_;
152 int cpu_avg_load_limit_, cpu_temp_limit_;
155 float mem_load_value_, avg_mem_load_high_value_, mem_load_limit_;
159 ff_msgs::CpuStateStamped cpu_state_msg_;
160 ff_msgs::MemStateStamped mem_state_msg_;
164 int assert_load_high_fault_timeout_sec_, clear_load_high_fault_timeout_sec_;
170 int i = strlen(line);
171 const char* p = line;
172 for (; (*p < '0' || *p >
'9') && *p !=
'\0'; ++p) {}
179 std::size_t uri_begin = uri.find_first_of(
"/");
180 std::size_t uri_end = uri.find_last_of(
":");
181 if (std::string::npos != uri_begin && std::string::npos != uri_end &&
182 uri_begin <= uri_end) {
183 uri.erase(uri.begin() + uri_end, uri.end());
184 uri.erase(uri.begin(), uri.begin() + uri_begin + 2);
187 ROS_ERROR_STREAM(
"Invalid URI, returning ");
194 #endif // CPU_MEM_MONITOR_CPU_MEM_MONITOR_H_