关于QT多线程应用与ROS2的topic通讯(3.1)

6 篇文章 0 订阅
3 篇文章 0 订阅

1.目标实现一个子线程,防止ROS2在通讯过程中使用spin()对主线程的UI进行堵塞!!

因为,在主线程执行spin的时候会阻塞,所以我们想要通过多线程解决这个问题,同时可以通过主线程按键信号去控制话题的同断

首先我们已经有了话题文件:

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>


class SingleDogNode : public rclcpp::Node
{

public:
    explicit SingleDogNode(const std::string& name);

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);
};

wang2.cpp

#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"

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);
}

随后为了使得这个节点可可以在子线程中运行,因此我们创立一个子线程的运行空间

roswprker.h

#ifndef ROSWORKER_H
#define ROSWORKER_H

#include <QObject>
#include <QThread>
#include <memory>
#include <rclcpp/rclcpp.hpp>

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();

signals:
    void finished();

private:
    std::shared_ptr<rclcpp::Node> node_;
    QThread workerThread_;
    bool isRunning_;
};

#endif // ROSWORKER_H

rosworker.cpp文件

#include "rosworker.h"
#include <QDebug>

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()
{
    if (!isRunning_) {
        isRunning_ = true;
        // 确保每次启动前重新初始化 ROS 2 上下文
       /* if (!rclcpp::ok()) {//判读有无初始化,如果没有那么就重新初始化防止出现未初始化导致崩溃
            rclcpp::init(0, nullptr);
        }*/
        // 开始工作线程
        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();
    }
}

在mainwindow的使用 :(这里一定要注意!!rclcpp::init()与rclcpp::shutdown()成对出现!!因此为了避免重复初始化以及重复关闭情况所以需要用if进行判断,从而方式程序崩溃)

#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);


    // 按钮启动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);
        }
        rosWorker->start();
    });
    // 按钮停止ROSWorker
    connect(ui->pushButton_1, &QPushButton::clicked,this,[&](){rosWorker->stop();});
}

MainWindow::~MainWindow()
{
    rosWorker->stop();
    rclcpp::shutdown(); // 确保在退出时关闭ROS 2上下文
    delete ui;
}

效果展示:当没有点击按钮的时候没有节点产生

打开之后会初始化节点:

打开另外一个节点:

可以正常通讯(这时候疯狂点击也不会出现崩溃现象!)

然后点击关闭节点(疯狂点击也不会崩溃!!如果不加if判断很有可能会崩溃)可以看见正常关闭

并且可以重复打开:

  • 13
    点赞
  • 4
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
Qt中使用ROS2进行topic通讯需要使用ROS2的C++ API。以下是一些基本步骤: 1. 安装ROS2和Qt 2. 在Qt中创建一个C++项目 3. 在CMakeLists.txt中添加以下代码以链接ROS2: ``` find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(std_msgs REQUIRED) ``` 4. 在Qt中创建一个ROS2节点: ``` #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" class MyNode : public rclcpp::Node { public: MyNode() : Node("my_node") { publisher_ = this->create_publisher<std_msgs::msg::String>("my_topic", 10); timer_ = this->create_wall_timer(std::chrono::milliseconds(500), std::bind(&MyNode::publishMessage, this)); } private: void publishMessage() { auto message = std_msgs::msg::String(); message.data = "Hello, world!"; publisher_->publish(message); } rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_; rclcpp::TimerBase::SharedPtr timer_; }; ``` 5. 在Qt中订阅ROS2话题: ``` #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" class MyNode : public rclcpp::Node { public: MyNode() : Node("my_node") { subscriber_ = this->create_subscription<std_msgs::msg::String>("my_topic", 10, std::bind(&MyNode::receiveMessage, this, std::placeholders::_1)); } private: void receiveMessage(const std_msgs::msg::String::SharedPtr message) { qDebug() << "Received message: " << message->data.c_str(); } rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscriber_; }; ``` 这些是基本的步骤,你可以根据你的需求和情况进行调整。

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值