Skip to content

Commit f53557d

Browse files
author
Mehmet Emin BAŞOĞLU
committed
feat: change command to top again
Signed-off-by: Mehmet Emin BAŞOĞLU <memin@leodrive.ai>
1 parent 40cbc20 commit f53557d

File tree

2 files changed

+95
-45
lines changed

2 files changed

+95
-45
lines changed

system/autoware_component_monitor/src/component_monitor_node.cpp

+86-43
Original file line numberDiff line numberDiff line change
@@ -24,9 +24,9 @@ ComponentMonitor::ComponentMonitor(const rclcpp::NodeOptions & node_options)
2424
usage_pub_ = create_publisher<autoware_internal_msgs::msg::SystemUsage>(
2525
"component_system_usage", rclcpp::SensorDataQoS());
2626

27-
const auto p = bp::search_path("pidstat");
27+
const auto p = bp::search_path("top");
2828
if (p.empty()) {
29-
RCLCPP_ERROR_STREAM(get_logger(), "Couldn't find 'pidstat' in path.");
29+
RCLCPP_ERROR_STREAM(get_logger(), "Couldn't find 'top' in path.");
3030
rclcpp::shutdown();
3131
}
3232

@@ -38,6 +38,7 @@ void ComponentMonitor::timer_callback()
3838
{
3939
if (usage_pub_->get_subscription_count() == 0) return;
4040

41+
get_stats();
4142
get_cpu_usage();
4243
get_mem_usage();
4344
publish();
@@ -52,6 +53,32 @@ void ComponentMonitor::publish()
5253
usage_pub_->publish(usage_msg_);
5354
}
5455

56+
/**
57+
* @brief Get system usage of the component.
58+
*
59+
* @details The output of top -b -d 0.1 -n 1 -p PID` is like below:
60+
*
61+
* top - 15:32:33 up 4:34, 1 user, load average: 3,11, 4,51, 3,67
62+
* Tasks: 1 total, 0 running, 1 sleeping, 0 stopped, 0 zombie
63+
* %Cpu(s): 0,0 us, 0,8 sy, 0,0 ni, 99,2 id, 0,0 wa, 0,0 hi, 0,0 si, 0,0 st
64+
* MiB Mem : 63996,4 total, 11536,7 free, 34437,3 used, 18022,4 buff/cache
65+
* MiB Swap: 2048,0 total, 894,2 free, 1153,8 used. 27854,7 avail Mem
66+
*
67+
* PID USER PR NI VIRT RES SHR S %CPU %MEM TIME+ COMMAND
68+
* 2837 meb 20 0 2681404 1,0g 34796 S 0,0 1,6 19:48.66 awesome
69+
*
70+
* We get 5th, 8th, and 9th fields, which are RES, %CPU, and %MEM, respectively.
71+
*
72+
*/
73+
void ComponentMonitor::get_stats()
74+
{
75+
std::string cmd{"top -b -d 0.1 -n 1 -p "};
76+
cmd += std::to_string(pid_);
77+
78+
auto std_out = run_command(cmd);
79+
fields_ = get_fields(std_out);
80+
}
81+
5582
std::stringstream ComponentMonitor::run_command(const std::string & cmd) const
5683
{
5784
int out_fd[2];
@@ -104,6 +131,47 @@ std::vector<std::string> ComponentMonitor::get_fields(std::stringstream & std_ou
104131
return words;
105132
}
106133

134+
void ComponentMonitor::get_cpu_usage()
135+
{
136+
const auto & cpu_rate = fields_[8];
137+
usage_msg_.cpu_usage_rate = to_float(cpu_rate);
138+
}
139+
140+
void ComponentMonitor::get_mem_usage()
141+
{
142+
auto & mem_usage = fields_[5];
143+
const auto & mem_usage_rate = fields_[9];
144+
145+
uint64_t mem_usage_kib{};
146+
switch (mem_usage.back()) {
147+
case 'm':
148+
mem_usage.pop_back();
149+
mem_usage_kib = mib_to_kib(to_uint32(mem_usage));
150+
break;
151+
case 'g':
152+
mem_usage.pop_back();
153+
mem_usage_kib = gib_to_kib(to_uint32(mem_usage));
154+
break;
155+
case 't':
156+
mem_usage.pop_back();
157+
mem_usage_kib = tib_to_kib(to_uint32(mem_usage));
158+
break;
159+
case 'p':
160+
mem_usage.pop_back();
161+
mem_usage_kib = pib_to_kib(to_uint32(mem_usage));
162+
break;
163+
case 'e':
164+
mem_usage.pop_back();
165+
mem_usage_kib = eib_to_kib(to_uint32(mem_usage));
166+
break;
167+
default:
168+
mem_usage_kib = to_uint32(mem_usage);
169+
}
170+
171+
usage_msg_.mem_usage_kib = mem_usage_kib;
172+
usage_msg_.mem_usage_rate = to_float(mem_usage_rate);
173+
}
174+
107175
float ComponentMonitor::to_float(const std::string & str)
108176
{
109177
return std::strtof(str.c_str(), nullptr);
@@ -114,54 +182,29 @@ uint32_t ComponentMonitor::to_uint32(const std::string & str)
114182
return std::strtoul(str.c_str(), nullptr, 10);
115183
}
116184

117-
// cspell: ignore pidstat, leopc
118-
/**
119-
* @brief Get CPU usage of the component.
120-
*
121-
* @details The output of `pidstat -u -h 1 1 -p PID` is like below:
122-
*
123-
* Linux 6.5.0-35-generic (leopc) 21-05-2024 _x86_64_ (16 CPU)
124-
* 14:54:52 UID PID %usr %system %guest %wait %CPU CPU Command
125-
* 14:54:52 1000 3280 0,00 0,00 0,00 0,00 0,00 0 awesome
126-
*
127-
* We get the 7th field, which is %CPU.
128-
*/
129-
void ComponentMonitor::get_cpu_usage()
185+
uint64_t ComponentMonitor::mib_to_kib(uint64_t mebibytes)
130186
{
131-
std::string cmd{"pidstat -u -h 1 1 -p "};
132-
cmd += std::to_string(pid_);
133-
134-
auto std_out = run_command(cmd);
135-
const auto fields = get_fields(std_out);
136-
137-
const auto & cpu_rate = fields[7];
138-
usage_msg_.cpu_usage_rate = to_float(cpu_rate);
187+
return mebibytes * 1024;
139188
}
140189

141-
/**
142-
* @brief Get memory usage of the component.
143-
*
144-
* @details The output of `pidstat -r -h 1 1 -p PID` is like below:
145-
*
146-
* Linux 6.5.0-35-generic (leopc) 21-05-2024 _x86_64_ (16 CPU)
147-
* 14:54:52 UID PID minflt/s majflt/s VSZ RSS %MEM Command
148-
* 14:54:52 1000 3280 2426,99 0,00 1820884 1243692 1,90 awesome
149-
*
150-
* We get the 6th and 7th fields, which are RSS and %MEM, respectively.
151-
*/
152-
void ComponentMonitor::get_mem_usage()
190+
uint64_t ComponentMonitor::gib_to_kib(uint64_t gibibytes)
153191
{
154-
std::string cmd{"pidstat -r -h 1 1 -p "};
155-
cmd += std::to_string(pid_);
192+
return gibibytes * 1024 * 1024;
193+
}
156194

157-
auto std_out = run_command(cmd);
158-
const auto fields = get_fields(std_out);
195+
uint64_t ComponentMonitor::tib_to_kib(uint64_t tebibytes)
196+
{
197+
return tebibytes * 1024ULL * 1024ULL * 1024ULL;
198+
}
159199

160-
const auto & mem_usage = fields[6];
161-
const auto & mem_usage_rate = fields[7];
200+
uint64_t ComponentMonitor::pib_to_kib(uint64_t pebibytes)
201+
{
202+
return pebibytes * 1024ULL * 1024ULL * 1024ULL * 1024ULL;
203+
}
162204

163-
usage_msg_.mem_usage_bytes = to_uint32(mem_usage);
164-
usage_msg_.mem_usage_rate = to_float(mem_usage_rate);
205+
uint64_t ComponentMonitor::eib_to_kib(uint64_t exbibytes)
206+
{
207+
return exbibytes * 1024ULL * 1024ULL * 1024ULL * 1024ULL * 1024ULL;
165208
}
166209

167210
} // namespace autoware::component_monitor

system/autoware_component_monitor/src/component_monitor_node.hpp

+9-2
Original file line numberDiff line numberDiff line change
@@ -40,17 +40,24 @@ class ComponentMonitor : public rclcpp::Node
4040
private:
4141
void timer_callback();
4242
void publish();
43+
void get_stats();
4344
std::stringstream run_command(const std::string & cmd) const;
4445
static std::vector<std::string> get_fields(std::stringstream & std_out);
45-
static float to_float(const std::string & str);
46-
static uint32_t to_uint32(const std::string & str);
4746
void get_cpu_usage();
4847
void get_mem_usage();
48+
static float to_float(const std::string & str);
49+
static uint32_t to_uint32(const std::string & str);
50+
static uint64_t mib_to_kib(uint64_t mebibytes);
51+
static uint64_t gib_to_kib(uint64_t gibibytes);
52+
static uint64_t tib_to_kib(uint64_t tebibytes);
53+
static uint64_t pib_to_kib(uint64_t pebibytes);
54+
static uint64_t eib_to_kib(uint64_t exbibytes);
4955

5056
rclcpp::TimerBase::SharedPtr timer_;
5157
rclcpp::Publisher<autoware_internal_msgs::msg::SystemUsage>::SharedPtr usage_pub_;
5258

5359
pid_t pid_;
60+
std::vector<std::string> fields_{};
5461
autoware_internal_msgs::msg::SystemUsage usage_msg_{};
5562
};
5663

0 commit comments

Comments
 (0)