qt5 ros2 demo

ros2自带的qt5库和qt5会有冲突

简单解决方式先配置ros2环境,再配置qt环境(会导致海龟画面打不开)

或者在home下创建几个.qtinit .ros2init把需要的环境变量配置进去

代码是cv来的,现做个备份,方便日后copy

创建功能包ros2_qt_demo

main.cpp

#include "mainwindow.h"

#include <QApplication>

int main(int argc, char *argv[])
{
    QApplication a(argc, argv);
    MainWindow w;
    w.show();
    return a.exec();
}

mainwindow.h

#ifndef MAINWINDOW_H
#define MAINWINDOW_H


#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

#include <QMainWindow>
#include <QTimer>

QT_BEGIN_NAMESPACE
namespace Ui
{
    class MainWindow;
}
QT_END_NAMESPACE

class MainWindow : public QMainWindow
{
    Q_OBJECT

public:
    MainWindow(QWidget *parent = nullptr);
    ~MainWindow();

private slots:
    void on_pushButton_clicked();

private:
    Ui::MainWindow *ui;

private:
    // -------------------------------------
    // ros
    // -------------------------------------
    // node
    rclcpp::Node::SharedPtr node_;
    // pub
    rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
    // sub
    rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscriber_;
    // spin
    void initSpin(void);
    QTimer spin_timer_;
    // -------------------------------------
};
#endif // MAINWINDOW_H

mainwindow.cpp

#include "mainwindow.h"
#include "./ui_mainwindow.h"
#include <iostream>
#include <QDebug>
MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent), ui(new Ui::MainWindow)
{
    // -------------------------------------
    // ROS 初始化
    // -------------------------------------
    rclcpp::init(0, nullptr);
    // create node
    this->node_ = rclcpp::Node::make_shared("demo");
    // create topic pub
    this->publisher_ = this->node_->create_publisher<std_msgs::msg::String>("pub_topic", 10);
    // create topic sub
    this->subscriber_ = node_->create_subscription<std_msgs::msg::String>(
        "sub_topic", 10,
        [&](const std_msgs::msg::String::SharedPtr msg)
        {
            // 處理訂閱到的消息
            QString receivedMsg = QString::fromStdString(msg->data);
            std::cout << msg->data << std::endl;
            ui->textBrowser->append(receivedMsg);
        });
    this->initSpin();
    // -------------------------------------
    ui->setupUi(this);
}

MainWindow::~MainWindow()
{
    delete ui;

    // -------------------------------------
    // ROS 釋放
    // -------------------------------------
    this->spin_timer_.stop();
    rclcpp::shutdown();
    // -------------------------------------
}

void MainWindow::initSpin(void)
{
    this->spin_timer_.setInterval(1); // 1 ms
    QObject::connect(&this->spin_timer_, &QTimer::timeout, [&]()
                     { rclcpp::spin_some(node_); });
    this->spin_timer_.start();
}

void MainWindow::on_pushButton_clicked()
{
    QString text = ui->lineEdit->text();
    std::cout << text.toStdString() << std::endl;

    std_msgs::msg::String msg;
    msg.data = text.toStdString();
    publisher_->publish(msg);
}

 mainwindow.ui

<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
 <class>MainWindow</class>
 <widget class="QMainWindow" name="MainWindow">
  <property name="geometry">
   <rect>
    <x>0</x>
    <y>0</y>
    <width>394</width>
    <height>298</height>
   </rect>
  </property>
  <property name="windowTitle">
   <string>MainWindow</string>
  </property>
  <widget class="QWidget" name="centralwidget">
   <widget class="QWidget" name="">
    <property name="geometry">
     <rect>
      <x>20</x>
      <y>10</y>
      <width>332</width>
      <height>225</height>
     </rect>
    </property>
    <layout class="QGridLayout" name="gridLayout">
     <item row="0" column="0" colspan="2">
      <widget class="QLineEdit" name="lineEdit">
       <property name="text">
        <string>hello world!!!</string>
       </property>
      </widget>
     </item>
     <item row="0" column="2">
      <widget class="QPushButton" name="pushButton">
       <property name="text">
        <string>pub msg</string>
       </property>
      </widget>
     </item>
     <item row="1" column="0">
      <widget class="QLabel" name="label">
       <property name="text">
        <string>sub msg:</string>
       </property>
      </widget>
     </item>
     <item row="1" column="1" colspan="2">
      <widget class="QTextBrowser" name="textBrowser"/>
     </item>
    </layout>
   </widget>
  </widget>
  <widget class="QMenuBar" name="menubar">
   <property name="geometry">
    <rect>
     <x>0</x>
     <y>0</y>
     <width>394</width>
     <height>28</height>
    </rect>
   </property>
  </widget>
  <widget class="QStatusBar" name="statusbar"/>
 </widget>
 <resources/>
 <connections/>
</ui>

CMakeLists.txt

cmake_minimum_required(VERSION 3.8)
project(ros2_qt_demo)

# ------------------------------------------
# 使用 C++ 14
# ------------------------------------------
if(NOT CMAKE_CXX_STANDARD)
  set(CMAKE_CXX_STANDARD 14)
endif()

# ------------------------------------------
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# ------------------------------------------
# 設定編譯類型和相依套件 
# ------------------------------------------
# ros
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
# qt
find_package(Qt5 REQUIRED COMPONENTS Core Gui Widgets)

# ------------------------------------------
# 添加可執行文件 
# ------------------------------------------
add_executable(demo 
  src/main.cpp
  src/mainwindow.cpp
  src/mainwindow.h
  src/mainwindow.ui
)

# ------------------------------------------
# 鏈接依賴項
# ------------------------------------------
# ros
target_link_libraries(demo 
  ${rclcpp_LIBRARIES} 
)
# qt
target_link_libraries(demo 
  Qt5::Core 
  Qt5::Gui
  Qt5::Widgets
)

# ------------------------------------------
# 包含其他包的標頭檔路徑
# ------------------------------------------
ament_target_dependencies(demo 
  rclcpp
  std_msgs
)

# ------------------------------------------
# 設置自動MOC、UIC和RCC (與QT相關)
# ------------------------------------------
set_target_properties(demo PROPERTIES AUTOMOC ON)
set_target_properties(demo PROPERTIES AUTOUIC ON)
set_target_properties(demo PROPERTIES AUTORCC ON)
# ------------------------------------------

# 安装可执行文件
install(TARGETS demo
  DESTINATION lib/${PROJECT_NAME}
)


ament_package()

package.xml

<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
  <name>ros2_qt_demo</name>
  <version>0.0.0</version>
  <description>TODO: Package description</description>
  <maintainer email="makubex49@gmail.com">howard</maintainer>
  <license>TODO: License declaration</license>

  <buildtool_depend>ament_cmake</buildtool_depend>

  <test_depend>ament_lint_auto</test_depend>
  <test_depend>ament_lint_common</test_depend>

  <export>
    <build_type>ament_cmake</build_type>
  </export>
</package>

编译运行

colcon build --packages-select ros2_qt_demo、
. install/setup.bash
ros2 run ros2_qt_demo demo

  • 1
    点赞
  • 11
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值