Skip to content
Merged
7 changes: 7 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -52,14 +52,21 @@ file(GLOB SUPER_MEDIATOR_FILES
)

add_executable(am_super ${am_super_cpp_files})
target_link_libraries(am_super)
ament_target_dependencies(am_super ${dependencies})

add_executable(resource_monitor src/resource_monitor/resource_status_class.cpp
src/resource_monitor/resource_monitor_main.cpp
src/resource_monitor/resource_monitor_node.cpp)
ament_target_dependencies(resource_monitor ${dependencies})

install(DIRECTORY include/
DESTINATION include/
)

install(TARGETS
am_super
resource_monitor
DESTINATION lib/${PROJECT_NAME}
)

Expand Down
31 changes: 31 additions & 0 deletions include/resource_monitor/resource_monitor_node.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
#ifndef AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_MONITOR_NODE_H_
#define AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_MONITOR_NODE_H_


#include <resource_monitor/resource_status_class.h>

namespace am
{
class ResourceMonitorNode : public AMLifeCycle
{
public:
ResourceMonitorNode(const std::string &node_name);

~ResourceMonitorNode();

std::shared_ptr<am::ResourceStatus> resource_status_ = nullptr;

std::shared_ptr<am::ResourceStatus> getAMClass();

void setAMClass(std::shared_ptr<am::ResourceStatus> am_class);

bool configured_ = false;

// AMLifeCycle overrides
void heartbeatCB() override;
bool onCleanup() override;
bool onConfigure() override;
};
}

#endif /*AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_MONITOR_NODE_H_*/
50 changes: 50 additions & 0 deletions include/resource_monitor/resource_monitor_stats.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
#ifndef AM_LIDAR_BS_AM_LIDAR_BS_STATS_H_
#define AM_LIDAR_BS_AM_LIDAR_BS_STATS_H_

#include <super_lib/am_stat_list.h>
#include <super_lib/am_stat.h>
#include <super_lib/am_stat_reset.h>
#include <super_lib/am_stat_ave.h>
#include <super_lib/am_stat_status.h>

namespace am
{

class ResourceMonitorStats
{
public:
AMStatStatus statStatus = AMStatStatus("ss", "AMStatStatus");


AMStat tf_stats = AMStat("tf_s", "Transform Stats", 1, 2, 80, 99);
AMStat node_stats = AMStat("n_s", "Nodes Stats", 1, 2, 80, 99);
AMStat cpu_stats = AMStat("cpu_s", "CPU Stats", 1, 2, 80, 99);
AMStat gpu_stats = AMStat("gpu_s", "GPU Stats", 1, 2, 80, 99);
AMStat ram_stats = AMStat("ram_s", "RAM Stats", 1, 2, 80, 99);
AMStat drive_stats = AMStat("drive_s", "Drive Stats", 1, 2, 80, 99);
AMStat lidar_ip = AMStat("lidar_ip_s", "Lidar IP Stats", 1, 2, 80, 99);
AMStat fl_ip = AMStat("fl_s", "FL IP Stats", 1, 2, 80, 99);
AMStat fr_ip = AMStat("fr_s", "FR IP Stats", 1, 2, 80, 99);
AMStat rl_ip = AMStat("rl_s", "RL IP Stats", 1, 2, 80, 99);
AMStat rr_ip = AMStat("rr_s", "RR IP Stats", 1, 2, 80, 99);

ResourceMonitorStats(AMStatList &stat_list)
{
stat_list.add(&statStatus);
stat_list.add(&tf_stats);
stat_list.add(&node_stats);
stat_list.add(&gpu_stats);
stat_list.add(&cpu_stats);
stat_list.add(&ram_stats);
stat_list.add(&drive_stats);
stat_list.add(&lidar_ip);
stat_list.add(&fl_ip);
stat_list.add(&fr_ip);
stat_list.add(&rl_ip);
stat_list.add(&rr_ip);
}
};

}; // namespace

#endif /* AM_LIDAR_BS_AM_LIDAR_BS_STATS_H_ */
159 changes: 159 additions & 0 deletions include/resource_monitor/resource_status_class.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,159 @@
#ifndef AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_STATUS_CLASS_H_
#define AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_STATUS_CLASS_H_

#include <iostream>
#include <am_utils/am_ros2_utility.h>

#include <iostream>
#include <fstream>
#include <sstream>
#include <string>
#include <unistd.h>
#include <vb_util_lib/transformer.h>
#include <resource_monitor/resource_monitor_stats.h>
#include <std_msgs/msg/int32.hpp>
#include <sys/statvfs.h> // For statvfs
#include <iomanip> // For std::setprecision


namespace am
{

struct MemoryInfo
{
unsigned long total;
unsigned long free;
unsigned long used;
unsigned long available;
int used_percent;
};

struct GpuInfo
{
std::string gpu_name;
int temp;
int load_percent;
};

struct CpuInfo
{
unsigned long long user;
unsigned long long nice;
unsigned long long system;
unsigned long long idle;
unsigned long long iowait;
unsigned long long irq;
unsigned long long softirq;
unsigned long long steal;
unsigned long long total;
};

struct DiskInfo {
unsigned long long totalSpace; // Total space in bytes
unsigned long long availableSpace; // Available space in bytes (matches `df`)
unsigned long long usedSpace; // Used space in bytes
double percentUsed; // Percentage used
};

class ResourceStatus
{
public:
ResourceStatus(std::shared_ptr<am::ResourceMonitorStats> stats);

~ResourceStatus();

am::MemoryInfo& getMemoryInfo();

am::CpuInfo getCPUInfo();

am::GpuInfo getGPUInfo();

void getCPUInfo(std::vector<am::CpuInfo> &infos);

DiskInfo getDiskInfo(const std::string& path = "/");

double calculateCpuLoad(const am::CpuInfo &ci, const am::CpuInfo &ci_old);

double getUpTime();

void updateInfos();

void print();

bool isReachable(const std::string &ipAddress);

void getParams();

std::unordered_set<std::string> getActiveIPs(const std::string& subnet = "192.168.1.0/24");

std::shared_ptr<am::ResourceMonitorStats> getStats();

std::vector<std::string> getInetAddresses();

// AMLifeCycle passthrus
bool onConfigure();

bool onCleanup();

void heartbeatCB();

private:

std::shared_ptr<am::ResourceMonitorStats> stats_;

rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr status_sub_;

rclcpp::Subscription<std_msgs::msg::Int32>::SharedPtr stat_sub_;

void statusCB(const std_msgs::msg::Int32::SharedPtr msg);

void statCB(const std_msgs::msg::Int32::SharedPtr msg);

int getCPUCoresCount();

std::string readFile(const std::string& path);

am::CpuInfo parseCpuLine(const std::string &line);

int cpu_cnt_= -1;

double cpu_usage_;

double uptime_seconds_;

bool ip_check_ {false};

bool is_first_time_ {true};

std::vector<double> cpu_loads_;

am::MemoryInfo mi;

std::vector<am::CpuInfo> cpu_infos_;

std::vector<am::CpuInfo> cpu_infos_old_;

am::GpuInfo gpu_info_;

std::vector<std::string> sub_nets_add_;

std::map<std::string, std::string> ip_addresses_; //IPAddress, Name

/*ROS Infrastructure Checking tools*/
std::shared_ptr<am::Transformer> transformer_;

std::vector<std::pair<std::string, std::string>> transform_list_;

rclcpp::TimerBase::SharedPtr timer_;

void timerCB();

void checkNodeNames();

void checkTransforms();

void checkSensorIPs();
};
}

#endif /*AM_SUPER_INCLUDE_RESOURCE_MONITOR_RESOURCE_STATUS_CLASS_H_*/
5 changes: 5 additions & 0 deletions src/am_super/am_super.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,7 @@ class AMSuper
rclcpp::Subscription<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr diagnostics_sub;
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr current_enu_sub;


rclcpp::Subscription<brain_box_msgs::msg::LogControl>::SharedPtr log_control_sub_;
BagLogger::BagLoggerLevel log_level_;

Expand Down Expand Up @@ -342,6 +343,8 @@ class AMSuper
current_enu_sub = am::Node::node->create_subscription<nav_msgs::msg::Odometry>(am_topics::CTRL_VX_VEHICLE_CURRENTENU, am::getSensorQoS(1),
std::bind(&AMSuper::currentENUCB, this, std::placeholders::_1));



}

~AMSuper()
Expand All @@ -353,6 +356,8 @@ class AMSuper
}

private:


/**
* process LifeCycleState messages from nodes
*
Expand Down
28 changes: 28 additions & 0 deletions src/resource_monitor/resource_monitor_main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
#include <am_utils/am_ros2_utility.h>

#include <resource_monitor/resource_monitor_stats.h>
#include <resource_monitor/resource_monitor_node.h>

std::shared_ptr<am::AMLifeCycle> am::Node::node = nullptr;

int main(int argc, char** argv)
{
rclcpp::init(argc, argv);

// create the AMLifeCycle object with stats and assign it to the AMNode singleton
std::shared_ptr<am::ResourceMonitorNode> am_node = std::make_shared<am::ResourceMonitorNode>("resource_monitor");
std::shared_ptr<am::ResourceMonitorStats> stats = std::make_shared<am::ResourceMonitorStats>(am_node->stats_list_);
am::Node::node = am_node;

// create the buisness logic object and give the AMLifecycle class a pointer to it
std::shared_ptr<am::ResourceStatus> am_class = std::make_shared<am::ResourceStatus>(stats);
am_node->setAMClass(am_class);

ROS_INFO_STREAM(am::Node::node->get_name() << ": running...");

rclcpp::spin(am::Node::node);

rclcpp::shutdown();

return 0;
}
65 changes: 65 additions & 0 deletions src/resource_monitor/resource_monitor_node.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
#include <am_utils/am_ros2_utility.h>
#include <super_lib/am_life_cycle.h>
#include <resource_monitor/resource_status_class.h>
#include <resource_monitor/resource_monitor_node.h>

namespace am
{

ResourceMonitorNode::ResourceMonitorNode(const std::string & node_name) : AMLifeCycle(node_name)
{
}

ResourceMonitorNode::~ResourceMonitorNode()
{

}

void ResourceMonitorNode::setAMClass(std::shared_ptr<ResourceStatus> am_class)
{
resource_status_= am_class;
}

std::shared_ptr<am::ResourceStatus> ResourceMonitorNode::getAMClass()
{
return resource_status_;
}

bool ResourceMonitorNode::onConfigure()
{
if(configured_)
{
return AMLifeCycle::onConfigure();
}

ROS_INFO("onConfigure");

if(!resource_status_->onConfigure())
{
ROS_WARN("am_class_->onConfigure() failed");
resource_status_->onCleanup();
return false;
}
else
{
configured_ = true;
return AMLifeCycle::onConfigure();
}
}

bool ResourceMonitorNode::onCleanup()
{
ROS_INFO("onCleanup");

resource_status_->onCleanup();
return AMLifeCycle::onCleanup();
}

void ResourceMonitorNode::heartbeatCB()
{
resource_status_->heartbeatCB();
AMLifeCycle::heartbeatCB();
}


} // namespace
Loading
Loading