1 准备工作
2 自定义通信接口
3 系统信息获取与发布
4 测试QT
5 数据可视化显示
1 准备工作
需求分析:开发一个基于ROS 2话题通信的系统状态监听工具,能够实时获取系统(如CPU、内存、网络等)的运行状态,并通过可视化界面展示这些信息。 运行后,status_publisher
节点会定期采集系统状态数据并发布到话题,status_display
节点订阅这些数据,并在GUI界面上实时显示系统状态信息,如CPU使用率、内存使用率、网络流量等。
实现步骤:
-
定义自定义消息类型
创建一个接口功能包status_interfaces
,定义SystemStatus
消息格式。 -
系统状态数据发布
创建status_publisher
功能包,编写Python代码,使用psutil
库获取系统状态数据,并发布到sys_status
话题。 -
数据可视化显示
创建status_display
功能包,使用C++和Qt框架订阅sys_status
话题,并将数据实时显示在GUI界面上。
技术栈:
-
ROS 2:用于实现节点间通信和消息定义。
-
Python:用于系统状态数据采集和发布。
-
C++:用于实现数据可视化。
-
Qt:用于构建GUI界面。
-
psutil:用于获取系统状态数据。
创建工作空间: 首先进入创建一个文件夹,命名为chapt3,进入,右击空白处进入一个终端,输入代码创建一个工作空间
mkdir -p topic_practice_ws/src
2 自定义通信接口
创建接口:
进入src,打开终端,或者直接cd topic_practice_ws/src进入
创建一个接口功能包:
ros2 pkg create status_interfaces --build-type ament_cmake --dependencies rosidl_default_generators builtin_interfaces --license Apache-2.0
这个命令的作用是:
-
创建一个名为
status_interfaces
的新 ROS 2 功能包。 -
使用
ament_cmake
作为构建系统。 -
添加
rosidl_default_generators
和builtin_interfaces
作为依赖项。
在status_interfaces下面建msg,再在下面建SystemStatus.msg
完整目录:src/status_interfaces/msg/SystemStatus.msg
在msg里面编辑消息接口定义文件:
builtin_interfaces/Time stamp #记录时间戳
string host_name #系统名称
float32 cpu_percent #CPU使用率
float32 memory_percent #内存使用率
float32 memory_total #内存总量
float32 memory_available #剩余有效内存
float64 net_sent #网络发送数据总量
float64 net_recv #网络接收数据总量
注册接口:定义好数据接口文件后,需要在CMakeLists.txt 中对该文件进行注册,声明其为消息接口文件,并为其添加builtin_interfaces依赖,添加完成后CMakeLists.txt中的部分代码如图所示。
添加的代码是:
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/SystemStatus.msg"
DEPENDENCIES builtin_interfaces
)
还需要在package.xml中添加代码,声明这个功能包是一个消息接口功能包。
<member_of_group>rosidl_interface_packages</member_of_group>
构建运行: 接下来,构建,再查看一下接口是否构建成功。
命令如下:
(记住一定要退到工作空间topic_practice_ws下执行命令哦!)
(一般情况下,构建都是在工作空间下构建!)
colcon build
source install/setup.bash
ros2 interface show status_interfaces/msg/SystemStatus
成功查看消息接口!接下来我们使用接口来传递数据。
3 系统信息获取与发布
创建一个功能包: 在src中再创建一个功能包 status_publisher
ros2 pkg create status_publisher --build-type ament_python --dependencies rclpy_status_interfaces --license Apache-2.0
创建节点:打开status_publisher,新建一个py文件,如图所示:
内容如下:
import rclpy # 导入ROS 2的Python客户端库
from rclpy.node import Node # 导入Node类,用于创建节点
from status_interfaces.msg import SystemStatus # 导入自定义的消息类型SystemStatus
import psutil # 导入psutil库,用于获取系统状态信息
import platform # 导入platform库,用于获取系统信息
class SysStatusPub(Node): # 定义一个继承自Node的类SysStatusPub,用于发布系统状态
def __init__(self, node_name): # 初始化函数
super().__init__(node_name) # 调用父类(Node)的构造函数
self.status_publisher_ = self.create_publisher( # 创建一个发布者
SystemStatus, 'sys_status', 10) # 指定话题名称和队列大小
self.timer = self.create_timer(1, self.timer_callback) # 创建一个定时器,每秒触发一次
def timer_callback(self): # 定时器回调函数
cpu_percent = psutil.cpu_percent() # 获取CPU使用率
memory_info = psutil.virtual_memory() # 获取内存信息
net_io_counters = psutil.net_io_counters() # 获取网络I/O信息
msg = SystemStatus() # 创建一个SystemStatus消息实例
msg.stamp = self.get_clock().now().to_msg() # 获取当前时间戳并转换为ROS 2时间戳
msg.host_name = platform.node() # 获取主机名
msg.cpu_percent = cpu_percent # 设置CPU使用率
msg.memory_percent = memory_info.percent # 设置内存使用率
msg.memory_total = memory_info.total / 1024 / 1024 # 计算总内存量(GB)
msg.memory_available = memory_info.available / 1024 / 1024 # 计算可用内存量(GB)
msg.net_sent = net_io_counters.bytes_sent / 1024 / 1024 # 计算发送的网络数据量(GB)
msg.net_recv = net_io_counters.bytes_recv / 1024 / 1024 # 计算接收的网络数据量(GB)
self.get_logger().info(f'发布:{str(msg)}') # 打印日志信息
self.status_publisher_.publish(msg) # 发布消息
def main(): # 主函数
rclpy.init() # 初始化ROS 2
node = SysStatusPub('sys_status_pub') # 创建SysStatusPub节点实例
rclpy.spin(node) # 保持节点运行,等待回调函数被触发
rclpy.shutdown() # 关闭ROS 2
这段代码创建了一个ROS 2节点,名为SysStatusPub
,用于监控和发布系统的CPU使用率、内存使用情况和网络I/O数据。它首先导入必要的库和消息类型,然后定义了一个继承自Node
的类,该类初始化时创建了一个定时器,每秒触发一次回调函数。在回调函数中,它收集系统状态信息,创建一个消息对象,填充数据,然后发布到sys_status
话题上。最后,主函数初始化ROS 2,启动节点,并保持运行直到关闭。
注册节点: 还需要在setup.py中对节点进行注册,
'sys_status_pub=status_publisher.sys_status_pub:main',
构建运行: 打开终端,退回工作空间,构建功能包:
然后查看接口是否构建成功。
首先让系统找到位置,代码如下:
source install/setup.bash
再运行功能包下面的节点
ros2 run status_publisher sys_status_pub
成功打印!!!
4 测试QT
现在使用QT来创建一个简单的页面
创建功能包: 老样子,创建一个新的功能包status_display
ros2 pkg create status_display --build-type ament_cmake --dependencies rclcpp status_interfaces --license Apache-2.0
创建节点:在刚才新建功能包的src目录下建一个cpp文件,如图所示:
编辑代码:
#include <QApplication> // 引入 QApplication 类,用于管理应用程序的控制流程
#include <QLabel> // 引入 QLabel 类,用于显示文本标签
#include <QString> // 引入 QString 类,用于处理字符串
int main(int argc, char* argv[]) { // 主函数,程序的入口点
QApplication app(argc, argv); // 创建 QApplication 实例,管理GUI程序的事件循环和资源
QLabel* label = new QLabel(); // 创建 QLabel 实例,用于显示文本
QString message = QString::fromStdString("Hello Qt!"); // 创建 QString 实例并初始化为 "Hello Qt!"
label->setText(message); // 设置标签文本为 message 字符串
label->show(); // 显示标签窗口
app.exec(); // 进入应用程序的事件循环,等待用户操作
return 0; // 返回 0 表示程序正常退出
}
这段代码是一个简单的Qt应用程序,用于创建一个窗口并在其中显示一条消息。
程序首先引入了Qt的三个核心组件:QApplication
、QLabel
和QString
。QApplication
管理应用程序的资源和事件循环;QLabel
用于在窗口中显示文本;QString
用于处理文本字符串。
在main
函数中,首先创建了一个QApplication
对象,它是每个Qt应用程序必须的。然后创建了一个QLabel
对象,并设置其文本为"Hello Qt!"
。最后,显示标签窗口并进入事件循环,等待用户操作直到应用程序关闭。
注册节点: 还要在CMakeLists.txt里面注册,完整代码如图:
cmake_minimum_required(VERSION 3.8)
project(status_display)
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(Qt5 REQUIRED COMPONENTS Widgets)
add_executable(hello_qt src/hello_qt.cpp)
target_link_libraries(hello_qt Qt5::Widgets)
install(TARGETS hello_qt
DESTINATION lib/${PROJECT_NAME}
)
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()
ament_package()
构建运行: 然后构建,运行这个例子,结果如图所示:
命令照着图片上敲一下,道理都一样,就不贴了
成功!!!!!!!!!!!!
5 数据可视化显示
创建节点: 新建文件sys_status_display.cpp,位置如图所示: (千万不要建错位置)
编写代码
#include <QApplication>
#include <QLabel>
#include <QString>
#include "rclcpp/rclcpp.hpp"
#include "status_interfaces/msg/system_status.hpp"
using SystemStatus = status_interfaces::msg::SystemStatus;
class SysStatusDisplay : public rclcpp::Node {
public:
SysStatusDisplay() : Node("sys_status_display") {
subscription_ = this->create_subscription<SystemStatus>(
"sys_status", 10, [&](const SystemStatus::SharedPtr msg) -> void {
label_->setText(get_qstr_from_msg(msg));
});
// 创建一个空的 SystemStatus 对象,转化成 QString 进行显示
label_ = new QLabel(get_qstr_from_msg(std::make_shared<SystemStatus>()));
label_->show();
}
QString get_qstr_from_msg(const SystemStatus::SharedPtr msg) {
std::stringstream show_str;
show_str
<< "===========系统状态可视化显示工具============\n"
<< "数 据 时 间:\t" << msg->stamp.sec << "\ts\n"
<< "用 户 名:\t" << msg->host_name << "\t\n"
<< "CPU使用率:\t" << msg->cpu_percent << "\t%\n"
<< "内存使用率:\t" << msg->memory_percent << "\t%\n"
<< "内存总大小:\t" << msg->memory_total << "\tMB\n"
<< "剩余有效内存:\t" << msg->memory_available << "\tMB\n"
<< "网络发送量:\t" << msg->net_sent << "\tMB\n"
<< "网络接收量:\t" << msg->net_recv << "\tMB\n"
<< "==========================================";
return QString::fromStdString(show_str.str());
}
private:
rclcpp::Subscription<SystemStatus>::SharedPtr subscription_;
QLabel* label_;
};
int main(int argc, char* argv[]) {
rclcpp::init(argc, argv);
QApplication app(argc, argv);
auto node = std::make_shared<SysStatusDisplay>();
std::thread spin_thread([&]() -> void { rclcpp::spin(node); });
spin_thread.detach();
app.exec();
rclcpp::shutdown();
return 0;
}
注册节点: 修改CMakeLists.txt,添加代码,,完整代码如下:
cmake_minimum_required(VERSION 3.8)
project(status_display)
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(Qt5 REQUIRED COMPONENTS Widgets)
add_executable(hello_qt src/hello_qt.cpp)
add_executable(sys_status_display src/sys_status_display.cpp)
target_link_libraries(hello_qt Qt5::Widgets)
target_link_libraries(sys_status_display Qt5::Widgets)
ament_target_dependencies(sys_status_display rclcpp status_interfaces)
install(TARGETS hello_qt
sys_status_display
DESTINATION lib/${PROJECT_NAME}
)
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()
ament_package()
构建运行: 打开终端,构建,运行该节点,命令如图所示:
成功运行!!!!!!观察到QT已经打开了,但是没有数据,因为还没有数据传过来,这个节点只是订阅与可视化数据。我们还需要发布数据。
如下图所示,运行发布者,发布数据,
然后观察QT界面,会发现已经成功接手到数据了。
大功告成!!!!!!!!!!!!