在ROS中将视频以图片消息的形式发布到/camera/image节点,可以采用cv::imshow函数将视频以一个单独的窗口显示出来,那如果采用Qt做上位机界面,能否将其显示在QT的界面中呢?答案是肯定的,由于接触qt和ROS不久,之前我真的是花了好长时间也没有解决,后来没事就找找相关知识,隔三差五拿出来试试,尝试了N中方法,终于今天在rqt工具中找到了灵感,其实这就是个qt多线程通信问题,于是一鼓作气,顺利将历史遗留问题解决,抓紧写个博客和各位博友分享喜悦!
rqt是ROS下的一款可视化工具(rqt is a Qt-based framework for GUI development for ROS),里面可以加载各种各样的插件,基于Qt实现,载入image_view 插件即可显示视频,你想啊,它是qt实现的,那么我肯定也可以啊,于是github找到源码:ros-visualization/rqt_image_view,仔细拜读了一番,找到关键所在 : #include
首先利用catkin_create_qt_pkg 创建一个包 在Qt Creator 中打开(已安rqt_ros_plugin插件,不懂,看前期文章),向界面中添加标签label_camera(rqt_image_view 是继承的QFrame类显示在QWidget部件上的),放哪你随意。
//add前为添加代码(...代表中间省略了,只贴出改动部分代码,下同!)
#include
#include "ui_main_window.h"
#include "qnode.hpp"
#include //added
#include //added
namespace mul_t {
class MainWindow : public QMainWindow {
Q_OBJECT
...
public Q_SLOTS:
...
void updateLogcamera();//added
void displayCamera(const QImage& image);//added
private:
Ui::MainWindowDesign ui;
QNode qnode;
QImage qimage_;//added
mutable QMutex qimage_mutex_;//added
};
} // namespace mul_t
#endif // mul_t_MAIN_WINDOW_H
//添加头文件
#include
#include
#include
#include
#include
#include
...
public:
void myCallback_img(const sensor_msgs::ImageConstPtr& msg);//camera callback function
QImage image;
Q_SIGNALS:
...
void loggingCamera();//发出设置相机图片信号
...
private:
int init_argc;
char** init_argv;
ros::Publisher chatter_publisher;
QStringListModel logging_model;
image_transport::Subscriber image_sub;
cv::Mat img;
在构造函数中添加信号与槽的连接
/*********************
** Logging
**********************/
QObject::connect(&qnode,SIGNAL(loggingCamera()),this,SLOT(updateLogcamera()));
函数实现
void MainWindow::displayCamera(const QImage &image)
{
qimage_mutex_.lock();
qimage_ = image.copy();
ui.label_camera->setPixmap(QPixmap::fromImage(qimage_));
ui.label_camera->resize(ui.label_camera->pixmap()->size());
qimage_mutex_.unlock();
}
void MainWindow::updateLogcamera()
{
displayCamera(qnode.image);
}
#include "sensor_msgs/image_encodings.h"//added head file
void QNode::myCallback_img(const sensor_msgs::ImageConstPtr &msg)
{
try
{
cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8);
img = cv_ptr->image;
image = QImage(img.data,img.cols,img.rows,img.step[0],QImage::Format_RGB888);//change to QImage format
ROS_INFO("I'm setting picture in mul_t callback function!");
Q_EMIT loggingCamera();
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
}
}
在两个重载的初始化函数中添加
bool QNode::init(){
...
// Add your ros communications here.
image_transport::ImageTransport it(n);
image_sub = it.subscribe("camera/image",100,&QNode::myCallback_img,this); ...}
bool QNode::init(const std::string &master_url, const std::string &host_url) {
...
// Add your ros communications here.
image_transport::ImageTransport it(n);
image_sub = it.subscribe("camera/image",100,&QNode::myCallback_img,this); ...}
//run()函数改为以下就可以了
void QNode::run() {
log(Info,"I'm running!");
while (!ros::ok() ) {
std::cout << "Ros shutdown, proceeding to close the gui." << std::endl;
Q_EMIT rosShutdown();
}
}
find_package(catkin REQUIRED COMPONENTS
qt_build
roscpp
std_msgs
sensor_msgs
cv_bridge
image_transport
)
find_package(OpenCV REQUIRED)
include_directories(
include
${catkin_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS})
...
target_link_libraries(mul_t ${QT_LIBRARIES} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
...
...
target_link_libraries(mul_t ${QT_LIBRARIES} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES})
...
...
opencv2
opencv2
message_generation
message_runtime
std_msgs sensor_msgs cv_bridge image_transport
std_msgs sensor_msgs cv_bridge image_transport
...
启动相机,运行程序!wonderful!
官方文档,开源代码就是最好的学习资料!
https://github.com/sunyuzhe2017/CSDN
//发布消息程序
msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", frame).toImageMsg();
//接收解码程序
cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8);