Qt调用ros库(qmake)

一、环境:

系统版本:ubuntu20.04

ros版本:noetic

qt版本:6.8.1

二、配置qt creator的启动文件

这一步主要是在qt启动时能加载ros的环境变量

sudo gedit ~/.local/share/applications/org.qt-project.qtcreator.desktop 

org.qt-project.qtcreator.desktop这个启动文件的名字可能不一样,核对里面的内容一样就可以,qt启动文件内容如下

[Desktop Entry]
Type=Application
Exec="/home/lenovo/Qt/Tools/QtCreator/bin/qtcreator" %F
Name=Qt Creator
GenericName=The IDE of choice for Qt development.
Icon=QtProject-qtcreator
StartupWMClass=qtcreator
Terminal=false
Categories=Development;IDE;Qt;
MimeType=text/x-c++src;text/x-c++hdr;text/x-xsrc;application/x-designer;application/vnd.qt.qmakeprofile;application/vnd.qt.xml.resource;text/x-qml;text/x-qt.qml;text/x-qt.qbs;

主要修改第三行,其余的不用修改,修改后的内容如下

[Desktop Entry]
Type=Application
Exec=bash -i -c /home/lenovo/Qt/Tools/QtCreator/bin/qtcreator
Name=Qt Creator
GenericName=The IDE of choice for Qt development.
Icon=QtProject-qtcreator
StartupWMClass=qtcreator
Terminal=false
Categories=Development;IDE;Qt;
MimeType=text/x-c++src;text/x-c++hdr;text/x-xsrc;application/x-designer;application/vnd.qt.qmakeprofile;application/vnd.qt.xml.resource;text/x-qml;text/x-qt.qml;text/x-qt.qbs;

三、配置.pro文件,添加ros头文件路径和动态链接库

INCLUDEPATH += /opt/ros/noetic/include
DEPENDPATH += /opt/ros/noetic/include
LIBS += -L/opt/ros/noetic/lib -lroscpp -lroslib -lrosconsole -lroscpp_serialization -lrostime -lrviz -limage_transport -lcv_bridge

第三行LIBS是动态链接库,主要是一些.so文件

四、qt订阅和发布话题

下面提供一个专门用于订阅、发布话题的类

qnode.h

#ifndef class1_ros_qt_demo_QNODE_HPP_
#define class1_ros_qt_demo_QNODE_HPP_

#ifndef Q_MOC_RUN
#include <ros/ros.h>
#endif

#include <QThread>
#include <QStringListModel>

#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <QImage>


namespace class1_ros_qt_demo {

class QNode : public QThread {
    Q_OBJECT
public:
    QNode(int argc, char** argv );
    virtual ~QNode();
    bool init();
    void run();

    QImage Mat2QImage(cv::Mat const& src);  // 图像格式转换函数

Q_SIGNALS:
    void rosShutdown();

    void image_vel(QImage);

private:
    int init_argc;
    char** init_argv;

    /********************************
    ** 发布者
    *********************************/
    ros::Publisher chatter_publisher;


    /********************************
    ** 订阅者
    *********************************/
    image_transport::Subscriber ImageData_sub;         // 视觉相机图像数据
    ros::Subscriber CloudPoint_sub;         // 深度相机点云数据



    /********************************
    ** 回调函数
    *********************************/
    void ImageData_callback(const sensor_msgs::ImageConstPtr &msg);  // 视觉相机图像数据
    void CloudPoint_callback(const sensor_msgs::PointCloud2 &msg);   // 深度相机点云数据
};

}  // namespace class1_ros_qt_demo

#endif /* class1_ros_qt_demo_QNODE_HPP_ */

qnode.cpp


#include "qnode.h"
#include <ros/ros.h>
#include <ros/network.h>
#include <string>
#include <std_msgs/String.h>
#include <sstream>


namespace class1_ros_qt_demo {

QNode::QNode(int argc, char** argv ) :
    init_argc(argc),
    init_argv(argv)
{}

QNode::~QNode() {
    if(ros::isStarted()) {
        ros::shutdown(); // 显式需要,因为我们使用ros::start();
        ros::waitForShutdown();
    }
    wait();
}

bool QNode::init() {
    ros::init(init_argc,init_argv,"class1_ros_qt_demo");
    if ( ! ros::master::check() ) {
        return false;
    }
    ros::start(); // 显式需要,因为我们的节点句柄超出了范围。
    ros::NodeHandle n;

    // Topic publisher
    chatter_publisher = n.advertise<std_msgs::String>("chatter", 1000);

    // Topic sublisher
    image_transport::ImageTransport it_(n);
    ImageData_sub = it_.subscribe("/img_cam",1000,&QNode::ImageData_callback,this);


    start();
    return true;
}

void QNode::run() {
    ros::Rate loop_rate(1);//频率

    int count = 0;
    while ( ros::ok() ) {

        std_msgs::String msg;
        std::stringstream ss;
        ss << "hello world " << count;
        msg.data = ss.str();
        chatter_publisher.publish(msg);
        ros::spinOnce();

        loop_rate.sleep();
        ++count;
    }
    std::cout << "Ros shutdown, proceeding to close the gui." << std::endl;
    Q_EMIT rosShutdown(); // used to signal the gui for a shutdown (useful to roslaunch)
}

// 图像格式转换函数
QImage QNode::Mat2QImage(cv::Mat const& src){
    QImage dest(src.cols, src.rows, QImage::Format_ARGB32);

    const float scale = 255.0;

    if (src.depth() == CV_8U) {
        if (src.channels() == 1) {
            for (int i = 0; i < src.rows; ++i) {
                for (int j = 0; j < src.cols; ++j) {
                    int level = src.at<quint8>(i, j);
                    dest.setPixel(j, i, qRgb(level, level, level));
                }
            }
        } else if (src.channels() == 3) {
            for (int i = 0; i < src.rows; ++i) {
                for (int j = 0; j < src.cols; ++j) {
                    cv::Vec3b bgr = src.at<cv::Vec3b>(i, j);
                    dest.setPixel(j, i, qRgb(bgr[2], bgr[1], bgr[0]));
                }
            }
        }
    } else if (src.depth() == CV_32F) {
        if (src.channels() == 1) {
            for (int i = 0; i < src.rows; ++i) {
                for (int j = 0; j < src.cols; ++j) {
                    int level = scale * src.at<float>(i, j);
                    dest.setPixel(j, i, qRgb(level, level, level));
                }
            }
        } else if (src.channels() == 3) {
            for (int i = 0; i < src.rows; ++i) {
                for (int j = 0; j < src.cols; ++j) {
                    cv::Vec3f bgr = scale * src.at<cv::Vec3f>(i, j);
                    dest.setPixel(j, i, qRgb(bgr[2], bgr[1], bgr[0]));
                }
            }
        }
    }
    return dest;
}


void QNode::ImageData_callback(const sensor_msgs::ImageConstPtr &msg)
{
    cv_bridge::CvImagePtr cv_ptr;
    cv_ptr = cv_bridge::toCvCopy(msg,msg->encoding);
    QImage im = Mat2QImage(cv_ptr->image);
    emit image_vel(im);
}



}  // namespace class1_ros_qt_demo

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值