< >
Home » ROS与Qt5人机交互 » ROS与Qt5人机交互界面开发-订阅图像话题并在界面中显示

ROS与Qt5人机交互界面开发-订阅图像话题并在界面中显示

ROS与Qt5人机交互界面开发-订阅图像话题并在界面中显示

说明:

  • 介绍如何订阅图像话题并在界面中显示

步骤:

  • 实现效果

请输入图片描述

  • 添加依赖
  • 首先在功能包的CMakeLists.txt中添加依赖
  • 如图:
find_package(catkin REQUIRED COMPONENTS rviz roscpp sensor_msgs
    cv_bridge
    std_msgs
    image_transport
    )
  • 订阅话题
 ros::NodeHandle n;
 image_transport::ImageTransport it_(n);
 image_sub=it_.subscribe(topic.toStdString(),100,&QNode::imageCallback0,this);
  • 回调函数处理图片数据
 //图像话题的回调函数
 void QNode::imageCallback0(const sensor_msgs::ImageConstPtr& msg)
 {
     cv_bridge::CvImagePtr cv_ptr;

     try
       {
         //深拷贝转换为opencv类型
         cv_ptr = cv_bridge::toCvCopy(msg, msg->encoding);
         QImage im=Mat2QImage(cv_ptr->image);
         emit Show_image(0,im);
       }
       catch (cv_bridge::Exception& e)
       {

         log(Error,("video frame0 exception: "+QString(e.what())).toStdString());
         return;
       }
 }
  • 在toCvCopy函数中,第二个参数需要指明图像的编码格式,否者会转换失败
  • 通过msg->encoding可以获取到图像话题的编码格式,传入即可。
//深拷贝转换为opencv类型
cv_ptr = cv_bridge::toCvCopy(msg, msg->encoding);
  • 发送自定义信号
emit Show_image(0,im);
  • 且将Mat类型的图片转为QImage类型图片函数:Mat2QImage
 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;
 }
  • 链接信号
  • 在mainwindows.cpp链接刚才回调函数中发出的信号:

//链接槽函数
connect(&qnode,SIGNAL(Show_image(int,QImage)),this,SLOT(slot_show_image(int,QImage)));

  • 槽函数中处理信号
  • 在槽函数中更新ui界面显示,在lable上显示图像:
void MainWindow::slot_show_image(int frame_id, QImage image)
{
 
        ui.label_video0->setPixmap(QPixmap::fromImage(image).scaled(ui.label_video0->width(),ui.label_video0->height()));
}

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros与qt5人机交互界面开发