ROS1 QT 中订阅压缩图像信息 实现流畅播放

笔者在学习蒋程扬老师的课程中,发现按照教程使用label标签显示原始图像(/camera/color/image_raw)会出现播放卡顿的现象,根据老师提示更换为显示压缩图像(/camera/color/image_raw/compressed),实现流畅播放。在此记录,以飨同学。

准备工作

读者首先需要安装好相机的驱动、ROS功能包,实现图像信息话题的发布,具体可见网络教程。

笔者的RealSense D435i ,配置好后发布的图像话题如下:

zhongren@zhongren-MS-7D42:~/Surgical_Robot$ rostopic list
/camera/color/camera_info
/camera/color/image_raw
/camera/color/image_raw/compressed
/camera/color/image_raw/compressed/parameter_descriptions
/camera/color/image_raw/compressed/parameter_updates
/camera/color/image_raw/compressedDepth
/camera/color/image_raw/compressedDepth/parameter_descriptions
/camera/color/image_raw/compressedDepth/parameter_updates
/camera/color/image_raw/theora
/camera/color/image_raw/theora/parameter_descriptions
/camera/color/image_raw/theora/parameter_updates
/camera/color/metadata
/camera/depth/camera_info
/camera/depth/color/points
/camera/depth/image_rect_raw
/camera/depth/image_rect_raw/compressed
/camera/depth/image_rect_raw/compressed/parameter_descriptions
/camera/depth/image_rect_raw/compressed/parameter_updates
/camera/depth/image_rect_raw/compressedDepth
/camera/depth/image_rect_raw/compressedDepth/parameter_descriptions
/camera/depth/image_rect_raw/compressedDepth/parameter_updates
/camera/depth/image_rect_raw/theora
/camera/depth/image_rect_raw/theora/parameter_descriptions
/camera/depth/image_rect_raw/theora/parameter_updates
/camera/depth/metadata
/camera/extrinsics/depth_to_color
/camera/motion_module/parameter_descriptions
/camera/motion_module/parameter_updates
/camera/pointcloud/parameter_descriptions
/camera/pointcloud/parameter_updates
/camera/realsense2_camera_manager/bond
/camera/rgb_camera/auto_exposure_roi/parameter_descriptions
/camera/rgb_camera/auto_exposure_roi/parameter_updates
/camera/rgb_camera/parameter_descriptions
/camera/rgb_camera/parameter_updates
/camera/stereo_module/auto_exposure_roi/parameter_descriptions
/camera/stereo_module/auto_exposure_roi/parameter_updates
/camera/stereo_module/parameter_descriptions
/camera/stereo_module/parameter_updates
/diagnostics
/rosout
/rosout_agg
/tf
/tf_static

这里只用到前面两个,原始图像话题和压缩后的图像话题。

实现逻辑

在qnode文件中订阅压缩图像信息,并转为QImage信号发送出去,在mainwindow文件中响应信号,并更新label组件所显示的信号。思路与蒋师教程相同,不同的只是订阅的图像消息类型。

qnode.hpp

首先包含要用到的头文件。

#include <std_msgs/String.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <QImage>
#include <sensor_msgs/CompressedImage.h>
#include <sensor_msgs/Image.h>

在类中定义图像信号,声明压缩图像信号订阅者,及其回调函数,这里还有一个cv图像转QImage图像的自定义函数。

这里尤其注意传入的参数类型。

    //图像信息
    void sig_img(QImage);

    ros::Subscriber cpsimg_sub;

    void img_cb(const sensor_msgs::CompressedImageConstPtr & img);

    QImage Mat2QImage(cv::Mat const& src);

F4,转至源文件。

qnode.cpp

在节点初始化函数中创建订阅者,并绑定回调函数。

cpsimg_sub=nh.subscribe("/camera/color/image_raw/compressed",1000,&QNode::img_cb,this);

这里注意话题名称,修改为你的压缩图像话题名称。

编写回调函数以及图像转换函数。


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::img_cb(const sensor_msgs::CompressedImageConstPtr &img)
{

    cv_bridge::CvImagePtr cvptr;
    try
    {
        //转化为CV形式的图像
        cvptr=cv_bridge::toCvCopy(img,sensor_msgs::image_encodings::BGR8);
    }
    catch(cv_bridge::Exception& e)
    {
        ROS_ERROR("cv_brige error: %s",e.what());
        return;
    }
    //compressed格式的图像不用红蓝交换
    cv::Mat cvColorImgMat=cvptr->image;
    QImage qimg=Mat2QImage(cvColorImgMat);
    emit sig_img(qimg);
}

回调函数中,简单的获取压缩图像信息,并将其转换为QImage类型,通过自定义信号类型发送出去。图像转换函数照抄即可。

信号发出,下面在mainwindow文件中进行处理。

main_window.hpp

首先在类中声明处理这个图像信号的槽函数,传入类型为QImage。

F4,转至源文件。

main_window.cpp

在主窗口函数中链接信号与槽函数。

QObject::connect(&qnode, SIGNAL(sig_img(QImage)), this, SLOT(slot_updimg(QImage)));

最后,编写处理信号的槽函数即可。

//    更新图像的槽函数
void MainWindow::slot_updimg(QImage qimg)
{
//    更新图像
    ui.lb_cpsimg->setPixmap(QPixmap::fromImage(qimg));
}

这里笔者只是简单的接受图像,并在label中显示。

运行效果

画面流畅,不再有卡顿。

2024年12月17日 屏幕视频


祝科研有进,前程似锦。

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值