Skip to content

Commit 8a8da82

Browse files
style(pre-commit): autofix
1 parent 16eeb9f commit 8a8da82

File tree

5 files changed

+154
-131
lines changed

5 files changed

+154
-131
lines changed

system/cgroup_setter/README.md

+15-9
Original file line numberDiff line numberDiff line change
@@ -17,51 +17,58 @@ The PID is found by `pgrep -f`.
1717

1818
### Node Parameters
1919

20-
| Name | Type | Default Value | Explanation | Reconfigurable |
21-
| --------------------------- | ------ | --------------------------------------------------- | --------------------------------------- | -------------- |
22-
| `cgroup_setting_config_path`| string | `$(find-pkg-share cgroup_setter)/config/cgroup.yaml`| yaml file path | |
20+
| Name | Type | Default Value | Explanation | Reconfigurable |
21+
| ---------------------------- | ------ | ---------------------------------------------------- | -------------- | -------------- |
22+
| `cgroup_setting_config_path` | string | `$(find-pkg-share cgroup_setter)/config/cgroup.yaml` | yaml file path | |
2323

2424
### YAML format for cgroup_setter
2525

2626
format
27+
2728
```yaml
2829
base_path: "/sys/fs/cgroup"
2930
settings:
3031
- directory: "xxx/xxx"
31-
search_word:
32+
search_word:
3233
- "xxxxx"
3334
- "xxxxx"
3435
- directory: "xxx/xxx"
35-
search_word:
36+
search_word:
3637
- "xxxxx"
3738
```
39+
3840
The following is an example of joining the PID from running `pgrep -f`
3941
with the keyword `__node:=system_monitor_container` to a cgroup named `/sys/fs/cgroup/autoware/system_monitor`.
4042

4143
example
44+
4245
```yaml
4346
base_path: "/sys/fs/cgroup"
4447
settings:
4548
- directory: "autoware/system_monitor"
46-
search_word:
49+
search_word:
4750
- "__node:=system_monitor_container"
4851
```
52+
4953
#### Rules
5054

5155
- The value of settings must be a sequence.
5256

5357
example
58+
5459
```yaml
5560
# NG
5661
base_path: "/sys/fs/cgroup"
5762
settings:
5863
directory: "autoware/system_monitor" # - directory
59-
search_word:
60-
- "__node:=system_monitor_container"
64+
search_word:
65+
- "__node:=system_monitor_container"
6166
```
67+
6268
- The value of search_word must be a sequence.
6369

6470
example
71+
6572
```yaml
6673
# NG
6774
base_path: "/sys/fs/cgroup"
@@ -86,4 +93,3 @@ TBD.
8693
```sh
8794
ros2 launch cgroup_setter cgroup_setter.launch.xml
8895
```
89-
+2-2
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
base_path: "/sys/fs/cgroup"
22
settings:
33
- directory: "autoware/system_monitor"
4-
search_word:
5-
- "__node:=system_monitor_container"
4+
search_word:
5+
- "__node:=system_monitor_container"

system/cgroup_setter/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212

1313
<depend>diagnostic_msgs</depend>
1414
<depend>diagnostic_updater</depend>
15-
<depend>yaml-cpp</depend>
1615
<depend>libboost-filesystem-dev</depend>
1716
<depend>rclcpp</depend>
1817
<depend>rclcpp_components</depend>
18+
<depend>yaml-cpp</depend>
1919

2020
<test_depend>ament_lint_auto</test_depend>
2121
<test_depend>autoware_lint_common</test_depend>

system/cgroup_setter/src/cgroup_setter.cpp

+118-101
Original file line numberDiff line numberDiff line change
@@ -18,47 +18,50 @@
1818
*/
1919

2020
#include "cgroup_setter.hpp"
21-
#include <iostream>
22-
#include <fstream>
23-
#include <sstream>
24-
#include <cstring>
25-
#include <unistd.h>
21+
2622
#include <boost/process.hpp>
23+
24+
#include <unistd.h>
2725
#include <yaml-cpp/yaml.h>
2826

27+
#include <cstring>
28+
#include <fstream>
29+
#include <iostream>
30+
#include <sstream>
31+
2932
namespace bp = boost::process;
3033

3134
CgroupSetter::CgroupSetter(const rclcpp::NodeOptions & options)
32-
: Node("cgroup_setter_node", options),
33-
updater_(this)
35+
: Node("cgroup_setter_node", options), updater_(this)
3436
{
3537
try {
3638
std::string yaml_path = this->declare_parameter<std::string>("cgroup_setting_config_path");
3739
YAML::Node config = YAML::LoadFile(yaml_path);
3840
if (config["base_path"]) {
39-
base_path_ = config["base_path"].as<std::string>();
41+
base_path_ = config["base_path"].as<std::string>();
4042
} else {
41-
RCLCPP_ERROR(this->get_logger(), "base_path is not set in the config file.");
42-
return;
43+
RCLCPP_ERROR(this->get_logger(), "base_path is not set in the config file.");
44+
return;
4345
}
4446

4547
if (!config["settings"]) {
46-
RCLCPP_ERROR(this->get_logger(), "settings is not set in the config file.");
47-
return;
48+
RCLCPP_ERROR(this->get_logger(), "settings is not set in the config file.");
49+
return;
4850
}
49-
51+
5052
for (auto setting : config["settings"]) {
51-
if (!setting["directory"] || !setting["search_word"]) {
53+
if (!setting["directory"] || !setting["search_word"]) {
5254
RCLCPP_ERROR(this->get_logger(), "directory or search_word is not set in the config file.");
5355
return;
54-
}
56+
}
5557

56-
for (auto word : setting["search_word"]) {
57-
std::pair<std::string, std::string> tmp_pair = std::make_pair(setting["directory"].as<std::string>(), word.as<std::string>());
58+
for (auto word : setting["search_word"]) {
59+
std::pair<std::string, std::string> tmp_pair =
60+
std::make_pair(setting["directory"].as<std::string>(), word.as<std::string>());
5861
cgroup_map_[tmp_pair] = false;
59-
}
62+
}
6063
}
61-
} catch (const std::exception& e) {
64+
} catch (const std::exception & e) {
6265
RCLCPP_ERROR(this->get_logger(), "Failed to load the config file.");
6366
return;
6467
}
@@ -73,58 +76,69 @@ CgroupSetter::CgroupSetter(const rclcpp::NodeOptions & options)
7376
this, this->get_clock(), 1s, std::bind(&CgroupSetter::checkProcessAndAddToCgroup, this));
7477
}
7578

76-
void CgroupSetter::checkCgroup(diagnostic_updater::DiagnosticStatusWrapper & stat) {
77-
bool allOK = true;
78-
for (auto& entry : cgroup_map_) {
79-
if (entry.second) {
80-
stat.add(entry.first.first + " " + entry.first.second, "OK");
81-
} else {
82-
allOK = false;
83-
stat.add(entry.first.first + " " + entry.first.second, "NG");
84-
}
85-
}
86-
if (allOK) {
87-
timer_->cancel();
88-
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "All processes are added to cgroup.");
79+
void CgroupSetter::checkCgroup(diagnostic_updater::DiagnosticStatusWrapper & stat)
80+
{
81+
bool allOK = true;
82+
for (auto & entry : cgroup_map_) {
83+
if (entry.second) {
84+
stat.add(entry.first.first + " " + entry.first.second, "OK");
8985
} else {
90-
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN, "Some processes are not added to cgroup.");
86+
allOK = false;
87+
stat.add(entry.first.first + " " + entry.first.second, "NG");
9188
}
89+
}
90+
if (allOK) {
91+
timer_->cancel();
92+
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "All processes are added to cgroup.");
93+
} else {
94+
stat.summary(
95+
diagnostic_msgs::msg::DiagnosticStatus::WARN, "Some processes are not added to cgroup.");
96+
}
9297
}
9398

94-
void CgroupSetter::checkProcessAndAddToCgroup() {
95-
for (auto& entry : cgroup_map_) {
96-
if (entry.second) {
97-
continue;
98-
}
99-
std::string word = entry.first.second;
100-
std::string result = executeCommand(word);
101-
if (!result.empty()) {
102-
std::istringstream iss(result);
103-
std::string pid;
104-
bool allAdded = true;
105-
while (std::getline(iss, pid, '\n')) {
106-
if (!pid.empty() && addToCgroup(entry.first.first, pid)) {
107-
if (checkPIDExists(base_path_ + "/" + entry.first.first + "/cgroup.procs", pid)) {
108-
RCLCPP_INFO(this->get_logger(), "Added all PIDs to cgroup. %s %s", entry.first.second.c_str(), pid.c_str());
109-
} else {
110-
allAdded = false;
111-
RCLCPP_ERROR(this->get_logger(), "Failed to add PID %s to cgroup. %s %s", pid.c_str(), entry.first.second.c_str(), result.c_str());
112-
}
113-
} else {
114-
allAdded = false;
115-
RCLCPP_ERROR(this->get_logger(), "Failed to add PID %s to cgroup. %s %s", pid.c_str(), entry.first.second.c_str(), result.c_str());
116-
}
117-
}
118-
if (allAdded) {
119-
entry.second = true;
120-
}
99+
void CgroupSetter::checkProcessAndAddToCgroup()
100+
{
101+
for (auto & entry : cgroup_map_) {
102+
if (entry.second) {
103+
continue;
104+
}
105+
std::string word = entry.first.second;
106+
std::string result = executeCommand(word);
107+
if (!result.empty()) {
108+
std::istringstream iss(result);
109+
std::string pid;
110+
bool allAdded = true;
111+
while (std::getline(iss, pid, '\n')) {
112+
if (!pid.empty() && addToCgroup(entry.first.first, pid)) {
113+
if (checkPIDExists(base_path_ + "/" + entry.first.first + "/cgroup.procs", pid)) {
114+
RCLCPP_INFO(
115+
this->get_logger(), "Added all PIDs to cgroup. %s %s", entry.first.second.c_str(),
116+
pid.c_str());
117+
} else {
118+
allAdded = false;
119+
RCLCPP_ERROR(
120+
this->get_logger(), "Failed to add PID %s to cgroup. %s %s", pid.c_str(),
121+
entry.first.second.c_str(), result.c_str());
122+
}
121123
} else {
122-
RCLCPP_ERROR(this->get_logger(), "Failed to get PID. %s %s", entry.first.second.c_str(), result.c_str());
124+
allAdded = false;
125+
RCLCPP_ERROR(
126+
this->get_logger(), "Failed to add PID %s to cgroup. %s %s", pid.c_str(),
127+
entry.first.second.c_str(), result.c_str());
123128
}
129+
}
130+
if (allAdded) {
131+
entry.second = true;
132+
}
133+
} else {
134+
RCLCPP_ERROR(
135+
this->get_logger(), "Failed to get PID. %s %s", entry.first.second.c_str(), result.c_str());
124136
}
137+
}
125138
}
126139

127-
std::string CgroupSetter::executeCommand(const std::string& search_word) {
140+
std::string CgroupSetter::executeCommand(const std::string & search_word)
141+
{
128142
int out_fd[2];
129143
if (pipe2(out_fd, O_CLOEXEC) != 0) {
130144
RCLCPP_ERROR(this->get_logger(), "pipe2 error");
@@ -140,11 +154,11 @@ std::string CgroupSetter::executeCommand(const std::string& search_word) {
140154
}
141155
bp::pipe err_pipe{err_fd[0], err_fd[1]};
142156
bp::ipstream is_err{std::move(err_pipe)};
143-
auto cmd=bp::search_path("pgrep");
157+
auto cmd = bp::search_path("pgrep");
144158
std::vector<std::string> args;
145159
args.push_back("-f");
146160
args.push_back(search_word);
147-
bp::child c(cmd, bp::args=args, bp::std_out > is_out, bp::std_err > is_err);
161+
bp::child c(cmd, bp::args = args, bp::std_out > is_out, bp::std_err > is_err);
148162
c.wait();
149163
if (c.exit_code() != 0) {
150164
std::ostringstream os;
@@ -159,47 +173,50 @@ std::string CgroupSetter::executeCommand(const std::string& search_word) {
159173
}
160174
}
161175

162-
bool CgroupSetter::checkPIDExists(const std::string& filePath, const std::string & pid) {
163-
std::ifstream file(filePath);
164-
if (!file.is_open()) {
165-
RCLCPP_ERROR(this->get_logger(), "Failed to open %s", filePath.c_str());
166-
return false;
167-
}
176+
bool CgroupSetter::checkPIDExists(const std::string & filePath, const std::string & pid)
177+
{
178+
std::ifstream file(filePath);
179+
if (!file.is_open()) {
180+
RCLCPP_ERROR(this->get_logger(), "Failed to open %s", filePath.c_str());
181+
return false;
182+
}
168183

169-
std::string line;
170-
while (std::getline(file, line)) {
171-
if (line == pid) {
172-
return true;
173-
}
184+
std::string line;
185+
while (std::getline(file, line)) {
186+
if (line == pid) {
187+
return true;
174188
}
175-
return false;
189+
}
190+
return false;
176191
}
177192

178-
bool CgroupSetter::addToCgroup(const std::string& cgroupPath, const std::string& pid) {
179-
std::string cgroupProcFile = base_path_ + "/" + cgroupPath + "/cgroup.procs";
180-
std::ofstream ofs(cgroupProcFile, std::ofstream::app);
181-
if (!ofs) {
182-
std::cerr << "Failed to open " << cgroupProcFile << std::endl;
183-
ofs.close();
184-
return false;
185-
}
186-
ofs << pid;
187-
if (!ofs) {
188-
std::cerr << "Failed to write to " << cgroupProcFile << std::endl;
189-
ofs.close();
190-
return false;
191-
}
193+
bool CgroupSetter::addToCgroup(const std::string & cgroupPath, const std::string & pid)
194+
{
195+
std::string cgroupProcFile = base_path_ + "/" + cgroupPath + "/cgroup.procs";
196+
std::ofstream ofs(cgroupProcFile, std::ofstream::app);
197+
if (!ofs) {
198+
std::cerr << "Failed to open " << cgroupProcFile << std::endl;
199+
ofs.close();
200+
return false;
201+
}
202+
ofs << pid;
203+
if (!ofs) {
204+
std::cerr << "Failed to write to " << cgroupProcFile << std::endl;
192205
ofs.close();
193-
return true;
206+
return false;
207+
}
208+
ofs.close();
209+
return true;
194210
}
195211

196-
int main(int argc, char ** argv) {
197-
rclcpp::init(argc, argv);
198-
rclcpp::executors::SingleThreadedExecutor executor;
199-
auto options = rclcpp::NodeOptions();
200-
auto node = std::make_shared<CgroupSetter>(options);
201-
executor.add_node(node);
202-
executor.spin();
203-
executor.remove_node(node);
204-
rclcpp::shutdown();
205-
}
212+
int main(int argc, char ** argv)
213+
{
214+
rclcpp::init(argc, argv);
215+
rclcpp::executors::SingleThreadedExecutor executor;
216+
auto options = rclcpp::NodeOptions();
217+
auto node = std::make_shared<CgroupSetter>(options);
218+
executor.add_node(node);
219+
executor.spin();
220+
executor.remove_node(node);
221+
rclcpp::shutdown();
222+
}

0 commit comments

Comments
 (0)