Skip to content

Commit c9dba1f

Browse files
authored
enable roslint (#4)
* enable roslint * fix diskmon.cpp roslint error * add roslint c++11 option * fix tempmon.cpp roslint error * remove lint control for c++11 feature * fix memmon.cpp roslint error * fix cpumon.cpp roslint error * fix netmon.cpp roslint error * move header file to include dir * fix util.h roslint error * test change for lgtm.com * add roslint instalation * remove install option
1 parent 9e23fec commit c9dba1f

File tree

9 files changed

+830
-696
lines changed

9 files changed

+830
-696
lines changed

CMakeLists.txt

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ add_compile_options(-std=c++11)
99
## is used, also find other catkin packages
1010
find_package(catkin REQUIRED COMPONENTS
1111
roscpp
12+
roslint
1213
std_msgs
1314
message_generation
1415
)
@@ -103,9 +104,9 @@ generate_messages(
103104
## CATKIN_DEPENDS: catkin_packages dependent projects also need
104105
## DEPENDS: system dependencies of this project that dependent projects also need
105106
catkin_package(
106-
# INCLUDE_DIRS include
107+
INCLUDE_DIRS include
107108
# LIBRARIES sysmon_ros
108-
CATKIN_DEPENDS roscpp std_msgs message_runtime
109+
CATKIN_DEPENDS roscpp roslint std_msgs message_runtime
109110
# DEPENDS system_lib
110111
)
111112

@@ -116,7 +117,7 @@ catkin_package(
116117
## Specify additional locations of header files
117118
## Your package locations should be listed before other locations
118119
include_directories(
119-
# include
120+
include
120121
${catkin_INCLUDE_DIRS}
121122
${Boost_INCLUDE_DIRS}
122123
)
@@ -181,6 +182,9 @@ target_link_libraries(diskmon
181182
${Boost_LIBRARIES}
182183
)
183184

185+
set(ROSLINT_CPP_OPTS "--filter=+,-build/c++11")
186+
roslint_cpp()
187+
184188
#############
185189
## Install ##
186190
#############

include/sysmon_ros/util.h

Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
/*
2+
* Copyright(c) 2019, seiga-k
3+
* All rights reserved.
4+
*/
5+
6+
#ifndef SYSMON_ROS_UTIL_H
7+
#define SYSMON_ROS_UTIL_H
8+
9+
#include <ros/ros.h>
10+
#include <ros/console.h>
11+
12+
#include <iostream>
13+
#include <fstream>
14+
#include <string>
15+
#include <vector>
16+
#include <numeric>
17+
18+
namespace Sysmon
19+
{
20+
21+
class Util
22+
{
23+
public:
24+
static bool readSingleLine(const std::string fname, std::string *outstr, const int32_t line = 0)
25+
{
26+
std::ifstream ifs;
27+
std::string str;
28+
int32_t cnt(line + 1);
29+
30+
ifs.open(fname.c_str());
31+
if (ifs.fail())
32+
{
33+
ROS_INFO("Could not open a file");
34+
return false;
35+
}
36+
while (cnt--)
37+
{
38+
str.clear();
39+
std::getline(ifs, str);
40+
if (ifs.fail())
41+
{
42+
// End of file
43+
return false;
44+
}
45+
}
46+
ifs.close();
47+
48+
*outstr = str;
49+
return true;
50+
}
51+
};
52+
53+
} // namespace Sysmon
54+
55+
#endif // SYSMON_ROS_UTIL_H

package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@
4949
<!-- Use doc_depend for packages you need only for building documentation: -->
5050
<!-- <doc_depend>doxygen</doc_depend> -->
5151
<buildtool_depend>catkin</buildtool_depend>
52+
<build_depend>roslint</build_depend>
5253
<depend>roscpp</depend>
5354
<depend>std_msgs</depend>
5455
<depend>message_generation</depend>

src/cpumon.cpp

Lines changed: 124 additions & 107 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,8 @@
1+
/*
2+
* Copyright(c) 2019, seiga-k
3+
* All rights reserved.
4+
*/
5+
16
#include <ros/ros.h>
27
#include <ros/console.h>
38
#include <std_msgs/Float32.h>
@@ -15,119 +20,131 @@
1520
#include <boost/phoenix.hpp>
1621
#include <boost/spirit/include/qi.hpp>
1722

18-
#include "util.h"
23+
#include "sysmon_ros/util.h"
1924

20-
namespace Sysmon {
25+
namespace Sysmon
26+
{
2127

22-
class Cpumon {
28+
class Cpumon
29+
{
2330
public:
24-
25-
Cpumon() :
26-
nh("~"),
27-
hz(1.0),
28-
do_loop(true),
29-
proc_name("/proc/stat"),
30-
cpun(0)
31-
{
32-
nh.getParam("hz", hz);
33-
struct stat f_stat;
34-
if (stat(proc_name.c_str(), &f_stat) == 0) {
35-
do_loop = true;
36-
std::string str;
37-
int32_t line(0);
38-
while (Util::readSingleLine(proc_name, str, line++)) {
39-
int32_t total, worker;
40-
std::string name;
41-
if (parse(str, total, worker, name)) {
42-
pub_usages.insert(std::make_pair(name, nh.advertise<std_msgs::Float32>(name, 1)));
43-
totals_prev.insert(std::make_pair(name, total));
44-
workers_prev.insert(std::make_pair(name, worker));
45-
}
46-
}
47-
48-
ROS_INFO("CPU Usage report is enaabled.");
49-
} else {
50-
do_loop = false;
51-
ROS_INFO("CPU Usage report is disabled.");
52-
}
53-
54-
ROS_INFO("Start cpumon node");
55-
}
56-
57-
~Cpumon()
58-
{
59-
}
60-
61-
void run()
62-
{
63-
ros::Rate rate(hz);
64-
while (ros::ok() && do_loop) {
65-
ros::spinOnce();
66-
67-
std::string str;
68-
int32_t line(0);
69-
while (Util::readSingleLine(proc_name, str, line++)) {
70-
int32_t total, worker;
71-
std::string name;
72-
if (parse(str, total, worker, name)) {
73-
std_msgs::Float32 usage;
74-
usage.data = (float)(worker - workers_prev[name]) / (float)(total - totals_prev[name]) * 100.;
75-
pub_usages[name].publish(usage);
76-
workers_prev[name] = worker;
77-
totals_prev[name] = total;
78-
}
79-
}
80-
81-
rate.sleep();
82-
}
83-
}
31+
Cpumon() :
32+
nh("~"),
33+
hz(1.0),
34+
do_loop(true),
35+
proc_name("/proc/stat"),
36+
cpun(0)
37+
{
38+
nh.getParam("hz", hz);
39+
struct stat f_stat;
40+
if (stat(proc_name.c_str(), &f_stat) == 0)
41+
{
42+
do_loop = true;
43+
std::string str;
44+
int32_t line(0);
45+
while (Util::readSingleLine(proc_name, &str, line++))
46+
{
47+
int32_t total, worker;
48+
std::string name;
49+
if (parse(str, &total, &worker, &name))
50+
{
51+
pub_usages.insert(std::make_pair(name, nh.advertise<std_msgs::Float32>(name, 1)));
52+
totals_prev.insert(std::make_pair(name, total));
53+
workers_prev.insert(std::make_pair(name, worker));
54+
}
55+
}
56+
57+
ROS_INFO("CPU Usage report is enaabled.");
58+
}
59+
else
60+
{
61+
do_loop = false;
62+
ROS_INFO("CPU Usage report is disabled.");
63+
}
64+
65+
ROS_INFO("Start cpumon node");
66+
}
67+
68+
~Cpumon()
69+
{
70+
}
71+
72+
void run()
73+
{
74+
ros::Rate rate(hz);
75+
while (ros::ok() && do_loop)
76+
{
77+
ros::spinOnce();
78+
79+
std::string str;
80+
int32_t line(0);
81+
while (Util::readSingleLine(proc_name, &str, line++))
82+
{
83+
int32_t total, worker;
84+
std::string name;
85+
if (parse(str, &total, &worker, &name))
86+
{
87+
std_msgs::Float32 usage;
88+
usage.data = static_cast<float>(worker - workers_prev[name])
89+
/ static_cast<float>(total - totals_prev[name])
90+
* 100.;
91+
pub_usages[name].publish(usage);
92+
workers_prev[name] = worker;
93+
totals_prev[name] = total;
94+
}
95+
}
96+
97+
rate.sleep();
98+
}
99+
}
84100

85101
private:
86-
bool parse(const std::string line, int32_t &total, int32_t &worker, std::string &cpu_name) {
87-
namespace qi = boost::spirit::qi;
88-
namespace bp = boost::phoenix;
89-
90-
auto first = line.begin();
91-
auto last = line.end();
92-
93-
std::vector<int32_t> results;
94-
std::string name;
95-
96-
if (qi::parse(
97-
first, last,
98-
(
99-
qi::as_string[qi::string("cpu") >> *qi::alnum][bp::ref(name) = qi::_1]
100-
>> +(+qi::blank >> qi::int_[bp::push_back(bp::ref(results), qi::_1)])
101-
)
102-
)) {
103-
//std::cout << "Match!! " << name << " " << results.size() << std::endl;
104-
if (results.size() == 10) {
105-
worker = results[0] + results[1] + results[2];
106-
total = std::accumulate(results.begin(), results.end(), 0);
107-
cpu_name = name;
108-
}
109-
110-
return true;
111-
}
112-
return false;
113-
}
114-
115-
ros::NodeHandle nh;
116-
std::map<std::string, ros::Publisher> pub_usages;
117-
std::map<std::string, int32_t> totals_prev;
118-
std::map<std::string, int32_t> workers_prev;
119-
double hz;
120-
bool do_loop;
121-
int32_t cpun;
122-
const std::string proc_name;
102+
bool parse(const std::string line, int32_t *total, int32_t *worker, std::string *cpu_name)
103+
{
104+
namespace qi = boost::spirit::qi;
105+
namespace bp = boost::phoenix;
106+
107+
auto first = line.begin();
108+
auto last = line.end();
109+
110+
std::vector<int32_t> results;
111+
std::string name;
112+
113+
if (qi::parse(
114+
first, last,
115+
(
116+
qi::as_string[qi::string("cpu") >> *qi::alnum][bp::ref(name) = qi::_1]
117+
>> +(+qi::blank >> qi::int_[bp::push_back(bp::ref(results), qi::_1)])
118+
))) // NOLINT
119+
{
120+
if (results.size() == 10)
121+
{
122+
*worker = results[0] + results[1] + results[2];
123+
*total = std::accumulate(results.begin(), results.end(), 0);
124+
*cpu_name = name;
125+
}
126+
127+
return true;
128+
}
129+
return false;
130+
}
131+
132+
ros::NodeHandle nh;
133+
std::map<std::string, ros::Publisher> pub_usages;
134+
std::map<std::string, int32_t> totals_prev;
135+
std::map<std::string, int32_t> workers_prev;
136+
double hz;
137+
bool do_loop;
138+
int32_t cpun;
139+
const std::string proc_name;
123140
};
124-
}
141+
} // namespace Sysmon
125142

126143
int main(int argc, char** argv)
127144
{
128-
ros::init(argc, argv, "cpumon");
129-
Sysmon::Cpumon cpumon;
130-
cpumon.run();
131-
ros::spin();
132-
return 0;
133-
}
145+
ros::init(argc, argv, "cpumon");
146+
Sysmon::Cpumon cpumon;
147+
cpumon.run();
148+
ros::spin();
149+
return 0;
150+
}

0 commit comments

Comments
 (0)