Skip to content
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.

Commit 3d066f1

Browse files
author
Mehmet Emin BAŞOĞLU
committedMay 22, 2024·
feat: add header and pid fields to msg
Signed-off-by: Mehmet Emin BAŞOĞLU <memin@leodrive.ai>
1 parent 240e327 commit 3d066f1

File tree

2 files changed

+12
-0
lines changed

2 files changed

+12
-0
lines changed
 

‎system/autoware_component_monitor/src/component_monitor_node.cpp

+10
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ ComponentMonitor::ComponentMonitor(const rclcpp::NodeOptions & node_options)
1717
}
1818

1919
pid_ = getpid();
20+
usage_msg_.pid = pid_;
2021
}
2122

2223
void ComponentMonitor::timer_callback()
@@ -25,6 +26,15 @@ void ComponentMonitor::timer_callback()
2526

2627
get_cpu_usage();
2728
get_mem_usage();
29+
publish();
30+
}
31+
32+
void ComponentMonitor::publish()
33+
{
34+
std_msgs::msg::Header header;
35+
header.stamp = now();
36+
header.frame_id = "component_monitor";
37+
usage_msg_.header = header;
2838
usage_pub_->publish(usage_msg_);
2939
}
3040

‎system/autoware_component_monitor/src/component_monitor_node.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
#include "rclcpp/rclcpp.hpp"
44

55
#include "autoware_internal_msgs/msg/system_usage.hpp"
6+
#include "std_msgs/msg/header.hpp"
67

78
#include "boost/filesystem.hpp"
89
#include "boost/process.hpp"
@@ -20,6 +21,7 @@ class ComponentMonitor : public rclcpp::Node
2021

2122
private:
2223
void timer_callback();
24+
void publish();
2325
std::stringstream run_command(const std::string & cmd) const;
2426
static std::vector<std::string> get_fields(std::stringstream & std_out);
2527
static float to_float(const std::string & str);

0 commit comments

Comments
 (0)
Please sign in to comment.