在这个例子中我实现了,一个通讯节点的类,同时我在另外一个类中实现了子线程的使用,并且在主窗口进行了实现。
其实有个简单方法,你也可以直接在通讯节点用子线程去实现。
这里说的是我的方法,在第二个方法一个外网教程如下:
Ubuntu22.04上でROS2とQtCreatorを連携させる(GUI制作編) #ROS2 - Qiita
首先先写.h文件,一定要记住该类一定要既要继承node而且也要继承QObject!!
// wang2.h
#ifndef WANG2_H
#define WANG2_H
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_msgs/msg/u_int32.hpp"
#include <QApplication>
#include <QThread>
#include <QPushButton>
#include <QSignalMapper>
#include <QObject>
class SingleDogNode : public QObject , public rclcpp::Node//同时继承了QObject,为了可以使用槽函数和connnect操作
{
Q_OBJECT // !!这个很关键使这个类成为Qt对象,可以使用信号和槽
public:
SingleDogNode(const std::string& name);
signals:
void messageReceived(const std_msgs::msg::String::SharedPtr msg); // 定义一个信号用来接受node传来的信号
private:
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_novel;//声明创建分开使用共享指针,这里,rclcpp::Subscription 是模板类,需要指定模板参数 std_msgs::msg::String 来表明订阅的消息类型是字符串类型。SharedPtr 是智能指针的一种,用于自动管理对象的生命周期,防止内存泄漏。
rclcpp::Publisher<std_msgs::msg::UInt32>::SharedPtr pub_money;
void topic_callback(const std_msgs::msg::String::SharedPtr msg);
};
#endif // WANG2_H
.cpp文件实现,在回调函数及的发送信息signals:
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "std_msgs/msg/u_int32.hpp"
#include <QApplication>
#include <QThread>
#include <QPushButton>
#include <QSignalMapper>
#include "wang2.h"
#include <QObject>
SingleDogNode::SingleDogNode(const std::string& name)
: Node(name) // 这里添加分号
{
// 打印一句自我介绍
RCLCPP_INFO(this->get_logger(), "大家好,我是单身狗%s.", name.c_str());
// 创建一个订阅者来订阅李四写的小说,通过名字 sexy_girl
sub_novel = this->create_subscription<std_msgs::msg::String>("sexy_girl", 10, std::bind(&SingleDogNode::topic_callback, this, std::placeholders::_1));
// 创建发布者
pub_money = this->create_publisher<std_msgs::msg::UInt32>("sexy_girl_money", 10);
}
void SingleDogNode::topic_callback(const std_msgs::msg::String::SharedPtr msg)
{
// 新建一张人民币
std_msgs::msg::UInt32 money;
money.data = 10;
// 发送人民币给李四
pub_money->publish(money);
RCLCPP_INFO(this->get_logger(), "朕已阅:'%s',打赏李四:%d 元的稿费", msg->data.c_str(), money.data);
emit messageReceived(msg);
}
下面介绍rosworker.h文件:
#ifndef ROSWORKER_H
#define ROSWORKER_H
#include <QObject>
#include <QThread>
#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
#include "src/wang2.h"
#include<QString>
class ROSWorker : public QObject
{
Q_OBJECT
public:
explicit ROSWorker(std::shared_ptr<rclcpp::Node> node, QObject *parent = nullptr);
~ROSWorker();
public slots:
void start();
void stop();
void processNovel(const std_msgs::msg::String::SharedPtr msg);
signals:
void finished();
void novelReceived(const QString& novel);
private:
std::shared_ptr<rclcpp::Node> node_;
QThread workerThread_;
bool isRunning_;
SingleDogNode* nodePtr=nullptr;
};
#endif // ROSWORKER_H
在写这个时候踩了一些坑:
1.为了保证node节点具有connect功能,我们这边传的参数可以是rclcpp::Node类的共享指针,但是后面必须使用static_cast<SingleDogNode*>进行转化!!否则没有connect操作!
2.这一段一定要放在构造函数中否则没有办法去连接信号
SingleDogNode* nodePtr = static_cast<SingleDogNode*>(node_.get());
connect (nodePtr,&SingleDogNode::messageReceived,this,&ROSWorker::processNovel);
// 现在你可以使用 nodePtr 作为 SingleDogNode 的指针
3.一定要注意! void novelReceived(const QString& novel); 里面参数为QString类型否则信号也没办法传过去(会报类型不正确)可以对函数传过来的参数进行强制转化。
void ROSWorker::processNovel(const std_msgs::msg::String::SharedPtr msg)
{
qDebug() << "emit";
emit novelReceived(QString::fromStdString(msg->data)); // 修复 emit 语句
}
下面介绍rosworker.cpp文件:(我们可以将connect函数与强制转化,移动到start函数内这样我们以后就可以直接在rosworker中直接进行信号的处理工作,去集成更多的节点类并且用信号方式使得他们可以在不同的地方进行调用!!这个很关键很符合我的想法!!)
#include "rosworker.h"
#include <QDebug>
#include<QString>
ROSWorker::ROSWorker(std::shared_ptr<rclcpp::Node> node, QObject *parent)
: QObject(parent), node_(node), isRunning_(false)
{
// 将ROSWorker对象移动到工作线程中
moveToThread(&workerThread_);
}
ROSWorker::~ROSWorker()
{
workerThread_.quit();
workerThread_.wait();
}
void ROSWorker::start()
{
SingleDogNode* nodePtr = static_cast<SingleDogNode*>(node_.get());
connect (nodePtr,&SingleDogNode::messageReceived,this,&ROSWorker::processNovel);
// 现在你可以使用 nodePtr 作为 SingleDogNode 的指针
if (!isRunning_) {
isRunning_ = true;
// 开始工作线程
workerThread_.start();
qDebug() << "open1";
// 开始执行工作
connect(&workerThread_, &QThread::started, this, [this]() {
qDebug() << "open2";
rclcpp::spin(node_);
emit finished();
isRunning_ = false;
});
}
}
void ROSWorker::stop()
{
if (isRunning_) {
// 停止执行工作
qDebug() << "close";
rclcpp::shutdown();
isRunning_ = false;
workerThread_.quit();
workerThread_.wait();
}
}
void ROSWorker::processNovel(const std_msgs::msg::String::SharedPtr msg)
{
qDebug() << "emit";
emit novelReceived(QString::fromStdString(msg->data)); // 修复 emit 语句
}
第二种callback的写法:
auto callback = [this](const std_msgs::msg::String::SharedPtr msg)
{
// 新建一张人民币
std_msgs::msg::UInt32 money;
money.data = 10;
// 发送人民币给李四
pub_money->publish(money);
RCLCPP_INFO(this->get_logger(), "朕已阅:'%s',打赏李四:%d 元的稿费", msg->data.c_str(), money.data);
emit messageReceived(msg);
};
subscription_ = create_subscription<std_msgs::msg::String>("sexy_girl", 10, callback);
mainwindow.cpp:
这个写到按键的connect里面,否则是没有办法找到rosworker这个对象的
connect(rosWorker,&ROSWorker::novelReceived,this,[=](const QString& nove){ui->textEdit->setText(nove);});
#include "mainwindow.h"
#include "ui_mainwindow.h"
#include <rclcpp/rclcpp.hpp>
#include <src/wang2.h>
#include "runnodes/rosworker.h"
MainWindow::MainWindow(QWidget *parent)
: QMainWindow(parent)
, ui(new Ui::MainWindow)
{
ui->setupUi(this);
connect(ui->pushButton_1, &QPushButton::clicked,this,[&](){rosWorker->stop();});
// 按钮启动ROSWorker
connect(ui->pushButton, &QPushButton::clicked, this,[&]()
{
// 初始化ROS 2
if (!rclcpp::ok()) {//判读有无初始化,如果没有那么就重新初始化防止出现未初始化导致崩溃
rclcpp::init(0, nullptr);
// 创建ROSWorker对象
auto node = std::make_shared<SingleDogNode>("wang2");
rosWorker = new ROSWorker(node);
connect(rosWorker,&ROSWorker::novelReceived,this,[=](const QString& nove){ui->textEdit->setText(nove);});
rosWorker->start();
}
});
// 按钮停止ROSWorker
}
MainWindow::~MainWindow()
{
rosWorker->stop();
rclcpp::shutdown(); // 确保在退出时关闭ROS 2上下文
delete ui;
}
大概是这个效果:
同时也是支持关闭的:并不会影响主线程的运行。