Skip to content

Commit d56fba7

Browse files
committed
Merge branch 'GV-3570/resource-monitor-report' into hardik/merge-check-with-system-monitor
2 parents bdcc697 + 1949776 commit d56fba7

File tree

8 files changed

+1135
-0
lines changed

8 files changed

+1135
-0
lines changed

CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,14 +52,21 @@ file(GLOB SUPER_MEDIATOR_FILES
5252
)
5353

5454
add_executable(am_super ${am_super_cpp_files})
55+
target_link_libraries(am_super)
5556
ament_target_dependencies(am_super ${dependencies})
5657

58+
add_executable(resource_monitor src/resource_monitor/resource_status_class.cpp
59+
src/resource_monitor/resource_monitor_main.cpp
60+
src/resource_monitor/resource_monitor_node.cpp)
61+
ament_target_dependencies(resource_monitor ${dependencies})
62+
5763
install(DIRECTORY include/
5864
DESTINATION include/
5965
)
6066

6167
install(TARGETS
6268
am_super
69+
resource_monitor
6370
DESTINATION lib/${PROJECT_NAME}
6471
)
6572

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
#ifndef AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_MONITOR_NODE_H_
2+
#define AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_MONITOR_NODE_H_
3+
4+
5+
#include <resource_monitor/resource_status_class.h>
6+
7+
namespace am
8+
{
9+
class ResourceMonitorNode : public AMLifeCycle
10+
{
11+
public:
12+
ResourceMonitorNode(const std::string &node_name);
13+
14+
~ResourceMonitorNode();
15+
16+
std::shared_ptr<am::ResourceStatus> resource_status_ = nullptr;
17+
18+
std::shared_ptr<am::ResourceStatus> getAMClass();
19+
20+
void setAMClass(std::shared_ptr<am::ResourceStatus> am_class);
21+
22+
bool configured_ = false;
23+
24+
// AMLifeCycle overrides
25+
void heartbeatCB() override;
26+
bool onCleanup() override;
27+
bool onConfigure() override;
28+
};
29+
}
30+
31+
#endif /*AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_MONITOR_NODE_H_*/
Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
#ifndef AM_LIDAR_BS_AM_LIDAR_BS_STATS_H_
2+
#define AM_LIDAR_BS_AM_LIDAR_BS_STATS_H_
3+
4+
#include <super_lib/am_stat_list.h>
5+
#include <super_lib/am_stat.h>
6+
#include <super_lib/am_stat_reset.h>
7+
#include <super_lib/am_stat_ave.h>
8+
#include <super_lib/am_stat_status.h>
9+
10+
namespace am
11+
{
12+
13+
class ResourceMonitorStats
14+
{
15+
public:
16+
AMStatStatus statStatus = AMStatStatus("ss", "AMStatStatus");
17+
18+
19+
AMStat tf_stats = AMStat("tf_s", "Transform Stats", 1, 2, 80, 99);
20+
AMStat node_stats = AMStat("n_s", "Nodes Stats", 1, 2, 80, 99);
21+
AMStat cpu_stats = AMStat("cpu_s", "CPU Stats", 1, 2, 80, 99);
22+
AMStat gpu_stats = AMStat("gpu_s", "GPU Stats", 1, 2, 80, 99);
23+
AMStat ram_stats = AMStat("ram_s", "RAM Stats", 1, 2, 80, 99);
24+
AMStat drive_stats = AMStat("drive_s", "Drive Stats", 1, 2, 80, 99);
25+
AMStat lidar_ip = AMStat("lidar_ip_s", "Lidar IP Stats", 1, 2, 80, 99);
26+
AMStat fl_ip = AMStat("fl_s", "FL IP Stats", 1, 2, 80, 99);
27+
AMStat fr_ip = AMStat("fr_s", "FR IP Stats", 1, 2, 80, 99);
28+
AMStat rl_ip = AMStat("rl_s", "RL IP Stats", 1, 2, 80, 99);
29+
AMStat rr_ip = AMStat("rr_s", "RR IP Stats", 1, 2, 80, 99);
30+
31+
ResourceMonitorStats(AMStatList &stat_list)
32+
{
33+
stat_list.add(&statStatus);
34+
stat_list.add(&tf_stats);
35+
stat_list.add(&node_stats);
36+
stat_list.add(&gpu_stats);
37+
stat_list.add(&cpu_stats);
38+
stat_list.add(&ram_stats);
39+
stat_list.add(&drive_stats);
40+
stat_list.add(&lidar_ip);
41+
stat_list.add(&fl_ip);
42+
stat_list.add(&fr_ip);
43+
stat_list.add(&rl_ip);
44+
stat_list.add(&rr_ip);
45+
}
46+
};
47+
48+
}; // namespace
49+
50+
#endif /* AM_LIDAR_BS_AM_LIDAR_BS_STATS_H_ */
Lines changed: 174 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,174 @@
1+
#ifndef AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_STATUS_CLASS_H_
2+
#define AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_STATUS_CLASS_H_
3+
4+
#include <iostream>
5+
#include <am_utils/am_ros2_utility.h>
6+
7+
#include <iostream>
8+
#include <fstream>
9+
#include <sstream>
10+
#include <string>
11+
#include <unistd.h>
12+
#include <vb_util_lib/transformer.h>
13+
#include <resource_monitor/resource_monitor_stats.h>
14+
#include <std_msgs/msg/int32.hpp>
15+
#include <sys/statvfs.h> // For statvfs
16+
#include <iomanip> // For std::setprecision
17+
#include <brain_box_msgs/msg/system_report.hpp>
18+
#include <vb_util_lib/bag_logger.h>
19+
#include <vb_util_lib/vb_main.h>
20+
#include <brain_box_msgs/msg/log_control.hpp>
21+
22+
namespace am
23+
{
24+
25+
struct MemoryInfo
26+
{
27+
unsigned long total;
28+
unsigned long free;
29+
unsigned long used;
30+
unsigned long available;
31+
int used_percent;
32+
};
33+
34+
struct GpuInfo
35+
{
36+
std::string gpu_name;
37+
int temp;
38+
int load_percent;
39+
};
40+
41+
struct CpuInfo
42+
{
43+
unsigned long long user;
44+
unsigned long long nice;
45+
unsigned long long system;
46+
unsigned long long idle;
47+
unsigned long long iowait;
48+
unsigned long long irq;
49+
unsigned long long softirq;
50+
unsigned long long steal;
51+
unsigned long long total;
52+
};
53+
54+
struct DiskInfo {
55+
unsigned long long totalSpace; // Total space in bytes
56+
unsigned long long availableSpace; // Available space in bytes (matches `df`)
57+
unsigned long long usedSpace; // Used space in bytes
58+
double percentUsed; // Percentage used
59+
};
60+
61+
class ResourceStatus
62+
{
63+
public:
64+
ResourceStatus(std::shared_ptr<am::ResourceMonitorStats> stats);
65+
66+
~ResourceStatus();
67+
68+
am::MemoryInfo& getMemoryInfo();
69+
70+
am::CpuInfo getCPUInfo();
71+
72+
am::GpuInfo getGPUInfo();
73+
74+
void getCPUInfo(std::vector<am::CpuInfo> &infos);
75+
76+
DiskInfo getDiskInfo(const std::string& path = "/");
77+
78+
double calculateCpuLoad(const am::CpuInfo &ci, const am::CpuInfo &ci_old);
79+
80+
double getUpTime();
81+
82+
void updateInfos(brain_box_msgs::msg::SystemReport &sys_report);
83+
84+
void print();
85+
86+
bool isReachable(const std::string &ipAddress);
87+
88+
void getParams();
89+
90+
std::unordered_set<std::string> getActiveIPs(const std::string& subnet = "192.168.1.0/24");
91+
92+
std::shared_ptr<am::ResourceMonitorStats> getStats();
93+
94+
std::vector<std::string> getInetAddresses();
95+
96+
// AMLifeCycle passthrus
97+
bool onConfigure();
98+
99+
bool onCleanup();
100+
101+
void heartbeatCB();
102+
103+
private:
104+
105+
std::shared_ptr<am::ResourceMonitorStats> stats_;
106+
107+
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr status_sub_;
108+
109+
rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr stat_sub_;
110+
111+
rclcpp::Subscription<brain_box_msgs::msg::LogControl>::SharedPtr log_ctrl_sub_;
112+
113+
rclcpp::Publisher<brain_box_msgs::msg::SystemReport>::SharedPtr sys_rep_pub_;
114+
115+
void statusCB(const std_msgs::msg::Int32::SharedPtr msg);
116+
117+
void statCB(const std_msgs::msg::Int32::SharedPtr msg);
118+
119+
void logCtrlCB(const brain_box_msgs::msg::LogControl::SharedPtr msg);
120+
121+
int getCPUCoresCount();
122+
123+
std::string readFile(const std::string& path);
124+
125+
am::CpuInfo parseCpuLine(const std::string &line);
126+
127+
int cpu_cnt_= -1;
128+
129+
double cpu_usage_;
130+
131+
double uptime_seconds_;
132+
133+
bool ip_check_ {false};
134+
135+
bool is_first_time_ {true};
136+
137+
BagLogger::BagLoggerLevel level_;
138+
139+
bool enabled_ {false};
140+
141+
std::vector<double> cpu_loads_;
142+
143+
std::string system_status_topic_ = "/resource_status";
144+
145+
am::MemoryInfo mi;
146+
147+
std::vector<am::CpuInfo> cpu_infos_;
148+
149+
std::vector<am::CpuInfo> cpu_infos_old_;
150+
151+
am::GpuInfo gpu_info_;
152+
153+
std::vector<std::string> sub_nets_add_;
154+
155+
std::map<std::string, std::string> ip_addresses_; //IPAddress, Name
156+
157+
/*ROS Infrastructure Checking tools*/
158+
std::shared_ptr<am::Transformer> transformer_;
159+
160+
std::vector<std::pair<std::string, std::string>> transform_list_;
161+
162+
rclcpp::TimerBase::SharedPtr timer_;
163+
164+
void timerCB();
165+
166+
void checkNodeNames(brain_box_msgs::msg::SystemReport &sys_report);
167+
168+
void checkTransforms(brain_box_msgs::msg::SystemReport &sys_report);
169+
170+
void checkSensorIPs(brain_box_msgs::msg::SystemReport &sys_report);
171+
};
172+
}
173+
174+
#endif /*AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_STATUS_CLASS_H_*/

src/am_super/am_super.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -212,6 +212,7 @@ class AMSuper
212212
rclcpp::Subscription<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr diagnostics_sub;
213213
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr current_enu_sub;
214214

215+
215216
rclcpp::Subscription<brain_box_msgs::msg::LogControl>::SharedPtr log_control_sub_;
216217
BagLogger::BagLoggerLevel log_level_;
217218

@@ -374,6 +375,8 @@ class AMSuper
374375
current_enu_sub = am::Node::node->create_subscription<nav_msgs::msg::Odometry>(am_topics::CTRL_VX_VEHICLE_CURRENTENU, am::getSensorQoS(1),
375376
std::bind(&AMSuper::currentENUCB, this, std::placeholders::_1));
376377

378+
379+
377380
}
378381

379382
~AMSuper()
@@ -385,6 +388,8 @@ class AMSuper
385388
}
386389

387390
private:
391+
392+
388393
/**
389394
* process LifeCycleState messages from nodes
390395
*
Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
#include <am_utils/am_ros2_utility.h>
2+
3+
#include <resource_monitor/resource_monitor_stats.h>
4+
#include <resource_monitor/resource_monitor_node.h>
5+
6+
std::shared_ptr<am::AMLifeCycle> am::Node::node = nullptr;
7+
8+
int main(int argc, char** argv)
9+
{
10+
rclcpp::init(argc, argv);
11+
12+
// create the AMLifeCycle object with stats and assign it to the AMNode singleton
13+
std::shared_ptr<am::ResourceMonitorNode> am_node = std::make_shared<am::ResourceMonitorNode>("resource_monitor");
14+
std::shared_ptr<am::ResourceMonitorStats> stats = std::make_shared<am::ResourceMonitorStats>(am_node->stats_list_);
15+
am::Node::node = am_node;
16+
17+
// create the buisness logic object and give the AMLifecycle class a pointer to it
18+
std::shared_ptr<am::ResourceStatus> am_class = std::make_shared<am::ResourceStatus>(stats);
19+
am_node->setAMClass(am_class);
20+
21+
ROS_INFO_STREAM(am::Node::node->get_name() << ": running...");
22+
23+
rclcpp::spin(am::Node::node);
24+
25+
rclcpp::shutdown();
26+
27+
return 0;
28+
}

0 commit comments

Comments
 (0)