ROS系統學習13---界面開發2

ROS系統學習13—界面開發2

上一篇文章介紹瞭如何搭建基於Qt5和librviz的ROS界面框架,這篇文章我們將進一步介紹怎麼用這個框架來實現一些常用的GUI顯示功能。

接收並顯示圖像消息

在ROS中,接收消息一般是用spin()或者spinOnce()兩個函數實現的。前者是一個阻塞函數,一運行程序則會等待在該函數處接收消息,後者則在調用之時方能接收到消息。如果寫過界面程序的老哥肯定清楚,這種性質的函數是不能寫在界面程序中的,否則程序將會處於假死狀態。因此在Qt中實現ROS消息的接收需要開闢新的線程來實現,比較主流的方法是將其全部封裝在一個類中,以接收並顯示圖像消息爲例,我們設計一個類如下:

qnode.h

#include <std_msgs/String.h> 
#include <ros/ros.h>
#include <QThread>
#include <image_transport/image_transport.h>
#include <opencv2/highgui/highgui.hpp>
#include <cv_bridge/cv_bridge.h>

class QNode : public QThread
{
    Q_OBJECT
public:
    QNode();
    virtual ~QNode();
    void run();
    bool init();
    void imageCallback(const sensor_msgs::ImageConstPtr& msg);//圖像接收後的回調函數
private:
    ros::Subscriber chatter_subscriber;//add
};

qnode.cpp

#include "qnode.h"

QNode::QNode()
{

}

QNode::~QNode()
{
    if(ros::isStarted())
    {
        ros::shutdown();
        ros::waitForShutdown();
    }
}

bool QNode::init() 
{
    start();
}

void QNode::imageCallback(const sensor_msgs::ImageConstPtr& msg)
{
    cv::imshow("view", cv_bridge::toCvShare(msg, "bgr8")->image);
}

void QNode::run()
{
    int argc = 0; char **argv = NULL;
    ros::init(argc, argv, "image_listener");
    ros::NodeHandle nh;
    image_transport::ImageTransport it(nh);
    image_transport::Subscriber sub = it.subscribe("/stereo/left/image_raw", 1, &QNode::imageCallback, this);
    while (nh.ok()) 
    {
        ros::spinOnce();
    }
}

這樣我們只要在主界面類中先聲明一個QNode對象qnode,之後在初始化的時候調用qnode.init()就可以直接接收並顯示圖像消息中的圖像了。

當然這一實現還不太完善,它的圖像顯示功能是通過OpenCV彈窗實現的,和GUI界面沒啥關係。如果想要將圖像放到Qt的窗體中顯示,可以藉助Qt的信號和槽的機制來實現。首先在QNode類中定義信號

Q_SIGNALS:
    void Show_image(QImage);

之後修改下回調函數,將收到的圖像轉爲QImage的格式之後以信號的形式進行發送。

void QNode::imageCallback(const sensor_msgs::ImageConstPtr& msg)
{
    //cpu 20%左右
    cv_bridge::CvImageConstPtr cv_ptr = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::RGB8);
    QImage image = QImage(cv_ptr->image.data,cv_ptr->image.cols,cv_ptr->image.rows,cv_ptr->image.step[0],QImage::Format_RGB888);//change  to QImage format
    emit Show_image(image);
}

注意:上面代碼的寫法不是最高效的,因爲其先將圖像消息轉爲OpenCV格式,之後再轉爲QImage格式,期間的兩次轉換消耗了一部分計算資源。代碼中的寫法是本人嘗試的一個比較高效的操作方式,因爲沒有找到可用的直接將圖像消息轉爲QImage格式的方法,最好的情況下只成功轉爲了黑白圖像,如果有老哥能給出操作那就實在太好了!

在Qt界面程序中聲明槽函數:

public slots:
    void slot_show_image(QImage);

定義函數:

void Qt_Ros_Test::slot_show_image(QImage image)
{
    ui->imageshow->setPixmap(QPixmap::fromImage(image).scaled(ui->imageshow->width(),ui->imageshow->height()));//ui->imageshow是個QLabel對象
}

然後綁定信號和槽就可以了:

connect(&qnode,SIGNAL(Show_image(QImage)),this,SLOT(slot_show_image(QImage)));

接收並顯示點雲消息

本人一開始顯示點雲是用librviz來完成的,結果發現性能和兼容性都有問題,於是換成了PCL來完成這件事情。操作如下:

包含PCL頭文件:

#include <pcl_ros/point_cloud.h>

訂閱點雲消息:

ros::Subscriber ptcloudSub = n.subscribe("ruby128", 1, &QNode::ptcloudCallback, this); //訂閱cloud節點

信號聲明:

Q_SIGNALS:
    void Show_ptcloud(pcl::PointCloud<pcl::PointXYZ>::Ptr);

回調函數聲明:

void ptcloudCallback(const sensor_msgs::PointCloudConstPtr &clouddata);//點雲接收後的回調函數

回調函數定義:

void QNode::ptcloudCallback(const sensor_msgs::PointCloudConstPtr &clouddata)
{
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);//聲明cloud 
    int getsize = clouddata->points.size();
    for (size_t i = 0; i < getsize; i++)
    {
        pcl::PointXYZ pt;
        pt.x=clouddata->points[i].x;
        pt.y=clouddata->points[i].y;
        pt.z=clouddata->points[i].z;
        cloud->push_back(pt);
    }
    cloud->height=1;
    cloud->width=getsize;
    emit Show_ptcloud(cloud);//通過Qt信號將點雲發送出去
}

上面的操作完成了點雲消息的接收並轉爲PCL的對像,以Qt信號的形式將點雲發送出去。接收並在Qt窗體內顯示點雲的操作比較麻煩,網上很多教程不太完整,本人搞了半天才發現原來還蠻簡單的。

聲明相關的頭文件

#include <pcl/visualization/cloud_viewer.h>  
#include <QVTKWidget.h>
#include <vtkRenderWindow.h>

定義相關的變量

bool haveinit=false;
boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer;//點雲顯示對象
QVTKWidget* qvtkWidget;
public slots:
    void slot_show_ptcloud(pcl::PointCloud<pcl::PointXYZ>::Ptr);

定義槽函數

void Qt_Ros_Test::slot_show_ptcloud(pcl::PointCloud<pcl::PointXYZ>::Ptr ptcloud)
{
    if(haveinit==false)
    {
        viewer->addPointCloud(ptcloud, "test");
        haveinit=true; 
    }
    viewer->updatePointCloud(ptcloud, "test"); 
    qvtkWidget->update();
}

初始化

viewer.reset(new pcl::visualization::PCLVisualizer("viewer",false));//設置點雲顯示對像
    //點雲顯示對象與Qt窗口綁定
    qvtkWidget = new QVTKWidget(ui->rvizwidget);
    qvtkWidget->resize(500, 400);
    qvtkWidget->SetRenderWindow(viewer->getRenderWindow());
    viewer->setupInteractor (qvtkWidget->GetInteractor (), qvtkWidget->GetRenderWindow());
    qRegisterMetaType<pcl::PointCloud<pcl::PointXYZ>::Ptr>("pcl::PointCloud<pcl::PointXYZ>::Ptr");//註冊信號對象類型
  connect(&qnode,SIGNAL(Show_ptcloud(pcl::PointCloud<pcl::PointXYZ>::Ptr)),this,SLOT(slot_show_ptcloud(pcl::PointCloud<pcl::PointXYZ>::Ptr)));//綁定信號和槽

搞定!

因爲用到了PCL,所以在"CMakeLists.txt"文件中要設置一下:

find_package(catkin REQUIRED COMPONENTS
  roscpp
  std_msgs
  rviz
  cv_bridge
  pcl_ros #add
  pcl_msgs #add
  PCL REQUIRED #add
)
include_directories(include ${PCL_INCLUDE_DIRS})
target_link_libraries(${PROJECT_NAME}_node  ${PCL_LIBRARIES})

用librviz顯示點雲消息(已棄用,原因在最後)

上一篇文章我們介紹了librviz的配置和簡單的使用,如果我們要將其嵌入到某個QWidget對象中,可以在初始化的時候傳這個對象給它:

MyViz* myviz = new MyViz(ui->rvizwidget);//rvizwidget爲QWidget對象
myviz->show();

用librviz顯示點雲對象非常簡單,代碼示例如下:

render_panel_ = new rviz::RenderPanel();
QVBoxLayout* main_layout = new QVBoxLayout;
main_layout->addWidget( render_panel_ );
setLayout( main_layout );
manager_ = new rviz::VisualizationManager( render_panel_ );
render_panel_->initialize( manager_->getSceneManager(), manager_ );
manager_->initialize();
manager_->startUpdate();
manager_->setFixedFrame("ruby128");//設置顯示的對象名稱
//創建一個類型爲rviz/PointCloud的圖層,用於接收topic爲/ruby128的點雲數據
rviz::Display *map_=manager_->createDisplay("rviz/PointCloud","pointCloud",true);
ROS_ASSERT(map_!=NULL);
map_->subProp("Topic")->setValue("/ruby128");//設置話題名稱
map_->subProp("Invert Rainbow")->setValue("true");
map_->subProp("Style")->setValue("Points");
map_->subProp("Size (Pixels)")->setValue("2");
map_->subProp("Color Transformer")->setValue("Intersity");
map_->subProp("Queue Size")->setValue("10");
map_->subProp("Alpha")->setValue("0.05");
//創建網格
grid_ = manager_->createDisplay( "rviz/Grid", "adjustable grid", true );
ROS_ASSERT( grid_ != NULL );
//設置網格格式
grid_->subProp( "Line Style" )->setValue( "Billboards" );
grid_->subProp( "Color" )->setValue( QColor( Qt::yellow ) );

然而用該代碼庫有兩個嚴重的缺點:

  1. 本人用上面的本文開頭的代碼顯示圖像,並用上面的代碼顯示點雲,之後發現兩者之間似乎有衝突,圖像經常出錯。
  2. 這個庫的性能不太行,不知道爲什麼CPU佔用比單純用RVIZ要高不少(本來RVIZ已經不怎麼樣了)。

參考文章:

https://blog.csdn.net/qq_38441692/category_9863968.html

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章