3.4.3系统信息获取与发布——c++版本代码
-
背景:
【《ROS 2机器人开发从入门到实践》3.4.3系统信息获取与发布】 https://www.bilibili.com/video/BV1GnH5eGEC3/?share_source=copy_web&vd_source=1a420da13de2005a4b95c85b21a48ff4
目前,该视频只有python版本的发布者代码,我已经照着视频改了一版cpp的代码。测试通过,可以正常运行。运行依赖于3.4.2节的接口和3.4.5的消息展示,这两节的内容课程中都有对应的cpp实现,所以,本篇文章只针对3.4.3节只有python实现的代码进行cpp实现。
代码:
src/status_publisher/src/sys_status_pub.cpp
#include "rclcpp/rclcpp.hpp" #include "status_interfaces/msg/system_status.hpp" #include "sys/sysinfo.h" #include <bits/local_lim.h> #include <cstring> #include <ctime> #include <fstream> #include <iostream> #include <sstream> #include <string> #include <unistd.h> using namespace std::chrono_literals; using SystemStatus = status_interfaces::msg::SystemStatus; class SysStatusPub : public rclcpp::Node { private: rclcpp::Publisher<SystemStatus>::SharedPtr _status_publiser; rclcpp::TimerBase::SharedPtr _timer; void timer_callback() { struct sysinfo info; if (sysinfo(&info) != 0) { RCLCPP_ERROR(this->get_logger(), "获取系统信息失败"); return; } /*TODO:计算CPU使用率*/ float cpu_percent = (float)(info.loads[0] * 100 / (1 << SI_LOAD_SHIFT)); /*获取内存信息*/ float memory_percent = (float)(info.totalram - info.freeram) / info.totalram * 100; float memory_total = (float)info.totalram / (1024 * 1024); float memory_available = (float)info.freeram / (1024 * 1024); /*获取网络I/O计数器*/ float net_sent = 0.0; float net_recv = 0.0; getNetworkIO(net_sent, net_recv); auto msg = std::make_shared<SystemStatus>(); /*获取当前时间并设置消息的时间戳*/ msg->stamp = this->get_clock()->now(); /*获取主机名*/ char hostname[HOST_NAME_MAX]; if (gethostname(hostname, HOST_NAME_MAX) == 0) { msg->host_name = hostname; } else { msg->host_name = "unknown"; } msg->cpu_percent = cpu_percent; msg->memory_percent = memory_percent; msg->memory_total = memory_total; msg->memory_available = memory_available; msg->net_sent = net_sent; msg->net_recv = net_recv; // RCLCPP_INFO(this->get_logger(), "发布:%s", rclcpp::tostring(*msg).c_str()); // std::cout<<msg<<std::endl; // rclcpp::fromStdstring /*发布消息*/ _status_publiser->publish(*msg); } /*从/proc/net/dev文件读取网络I/O信息并汇总字节数*/ void getNetworkIO(float &net_sent, float &net_recv) { std::ifstream file("/proc/net/dev"); if (!file) { RCLCPP_ERROR(this->get_logger(), "无法打开/proc/net/dev文件"); return; } std::string line; /*跳过文件头两行,头两行为标题信息等,不是具体数据*/ std::getline(file, line); std::getline(file, line); while (std::getline(file, line)) { std::stringstream iss(line); std::string interface; /*读取网络接口名称*/ std::getline(iss, interface, ':'); /*去除接口名称后的空格*/ interface.erase(interface.find_last_not_of(" \n\\t") + 1); /*对应接受和发送字节的位置,在文件中固定顺序*/ long long int bytes_recv, bytes_sent; iss >> bytes_recv; /*跳过中间其他统计数据,直接读取发送字节数*/ for (int i = 0; i < 7; ++i) { long long int t; iss >> t; } iss >> bytes_sent; net_recv += (float)bytes_recv / (1024 * 1024); net_sent += (float)bytes_sent / (1024 * 1024); } file.close(); } public: SysStatusPub() : Node("sys_status_pub") { /*创建发布者,话题名称为“sys_status”,队列长度为10*/ _status_publiser = this->create_publisher<SystemStatus>("sys_status", 10); /*创建定时器,每隔1s触发一次回调函数*/ _timer = this->create_wall_timer(std::chrono::seconds(1), std::bind(&SysStatusPub::timer_callback, this)); } }; int main(int argc, char **argv) { rclcpp::init(argc, argv); auto node = std::make_shared<SysStatusPub>(); rclcpp::spin(node); rclcpp::shutdown(); return 0; }
src/status_publisher/CMakeLists.txt
cmake_minimum_required(VERSION 3.8) project(status_publisher) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(status_interfaces REQUIRED) # find_package(rosidl_default_generators REQUIRED) add_executable(sys_status_pub src/sys_status_pub.cpp) ament_target_dependencies(sys_status_pub rclcpp status_interfaces) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) # the following line skips the linter which checks for copyrights # comment the line when a copyright and license is added to all source files set(ament_cmake_copyright_FOUND TRUE) # the following line skips cpplint (only works in a git repo) # comment the line when this package is in a git repo and when # a copyright and license is added to all source files set(ament_cmake_cpplint_FOUND TRUE) ament_lint_auto_find_test_dependencies() endif() install(TARGETS sys_status_pub DESTINATION lib/${PROJECT_NAME} ) ament_package()
启动
打开两个终端,分别进入你的工作空间目录下,分别执行sys_status_pub和sys_status_display。
wd@ubuntu22:~/cpp_proj/241224/topic_practice_workspace$ colcon build
wd@ubuntu22:~/cpp_proj/241224/topic_practice_workspace$ source install/setup.bash
在第一个终端运行:
wd@ubuntu22:~/cpp_proj/241224/topic_practice_workspace$ ros2 run status_display sys_status_display
在第二个终端运行:
wd@ubuntu22:~/cpp_proj/241224/topic_practice_workspace$ ros2 run status_publisher sys_status_pub
运行结果
因为图片用外链工具生成,不保证时效性,大家可以自己运行一下,看看结果。
-
在msg获取到系统状态信息后,python用RCLCPP_INFO输出msg内容,cpp不太会把共享指针指向的内容换成字符串输出。所以该部分没有实现,但是不打印msg并不影响发布msg的内容,对于结果是没有影响的。希望有大佬可以看看应该这里怎么做
-
@admin_ 不借助些复杂手段,没办法直接序列化msg成字符串并打印(C++中很不好做),只能自己手动拆msg,按照消息结构数据类型打印。
-
@小鱼 好滴,谢谢鱼总