ROS Qt5 librviz人机交互界面开发十二(订阅图像话题并在界面中显示)
原创
©著作权归作者所有:来自51CTO博客作者蒋程扬的部落格的原创作品,请联系作者获取转载授权,否则将追究法律责任
本系列教程文章专栏:
ROS机器人GUI程序开发

开发交流QQ群: 797497206
完整项目代码:
github
文章目录
- 一,实现效果
- 二,添加依赖
- 三,订阅话题
- 四,回调函数处理图片数据
- 五,链接信号
- 六,槽函数中处理信号
- 七,完整项目地址
- (转载请注明作者和出处、未经允许请勿用于商业用途)
这篇文章主要实现Qt中订阅Ros图像话题,并在界面中Label上显示
主要思路是在Qnode类中订阅图像话题,利用cv_bridge先转换为opencv的mat类型,再转换为QImage类型,通过自定义信号发送到mainwindow,并在label上显示。
一,实现效果

二,添加依赖
首先在功能包的CMakeLists.txt中添加依赖
(ensor_msgs
cv_bridge
image_transport)
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;
}
}
首先需要将消息转为opencv类型,在toCvCopy函数中,第二个参数需要指明图像的编码格式,否者会转换失败,通过msg->encoding可以获取到图像话题的编码格式,传入即可。
//深拷贝转换为opencv类型
cv_ptr = cv_bridge::toCvCopy(msg, msg->encoding);
接着将opencv类型转换为QImage类型(因为Label只能显示QImage类型的图像),通过Mat2QImage函数:
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;
}
接着发送自定义信号到mainwindow:
五,链接信号
在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()));
}
七,完整项目地址
在我自己学习的过程中目前发现没有相关类似完整开源项目,为了帮助其他人少走弯路,我决定将自己的完整项目开源:
github 创作不易,如果本教程对你有帮助,关注或点个赞吧,或者github标个星哦~~
您的支持就是我最大的动力~
(转载请注明作者和出处、 未经允许请勿用于商业用途)