一、qnode
qnode.hpp
GUI節點頭文件,繼承QThread 類,此爲Qt線程類,節點運行獨立於GUI,另開線程運行。
#ifndef qt_gui_QNODE_HPP_
#define qt_gui_QNODE_HPP_
#ifndef Q_MOC_RUN
#include <ros/ros.h>
#endif
#include <string>
#include <QThread>
#include <QStringListModel>
/*****************************************************************************
** Namespaces
*****************************************************************************/
namespace qt_gui {
/*****************************************************************************
** Class 繼承QThread線程類,在QThread類中,run()爲執行函數(類似於main())
*****************************************************************************/
class QNode : public QThread {
Q_OBJECT
public:
QNode(int argc, char** argv ); //初始化函數
virtual ~QNode(); //重寫關閉函數
//採用默認master名字和地址初始化節點
bool init();
//採用設置master名字和地址初始化節點
bool init(const std::string &master_url, const std::string &host_url);
//執行函數
void run();
//枚舉記錄信息
enum LogLevel {
Debug,
Info,
Warn,
Error,
Fatal
};
QStringListModel* loggingModel() { return &logging_model; }
void log( const LogLevel &level, const std::string &msg);
//qt信號
Q_SIGNALS:
void loggingUpdated(); //記錄更新信號
void rosShutdown(); //ros關閉的信號
private:
int init_argc;
char** init_argv;
ros::Publisher chatter_publisher;
QStringListModel logging_model;
};
} // namespace qt_gui
#endif /* qt_gui_QNODE_HPP_ */
qnode.cpp
#include <ros/ros.h>
#include <ros/network.h>
#include <string>
#include <std_msgs/String.h>
#include <sstream>
#include "../include/qt_gui/qnode.hpp"
/*****************************************************************************
** Namespaces
*****************************************************************************/
namespace qt_gui {
/*****************************************************************************
** Implementation
*****************************************************************************/
QNode::QNode(int argc, char** argv ) :
init_argc(argc),
init_argv(argv)
{}
QNode::~QNode() {
if(ros::isStarted()) {
ros::shutdown(); // 關閉ros節點,因爲初始化時使用了ros::start();
ros::waitForShutdown(); // 等待ros節點完全關閉
}
wait(); // 等待線程關閉
}
//兩種初始化方式
bool QNode::init() {
ros::init(init_argc,init_argv,"qt_gui");
//檢查master是否存在
if ( ! ros::master::check() )
{
return false;
}
ros::start(); // 節點處理超出範圍,因此需要ros::start()
ros::NodeHandle n;
//定義發佈器,根據需求可以進行修改
chatter_publisher = n.advertise<std_msgs::String>("chatter", 1000);
//啓動該節點
start();
return true;
}
bool QNode::init(const std::string &master_url, const std::string &host_url) {
std::map<std::string,std::string> remappings;
//映射master信息
remappings["__master"] = master_url;
remappings["__hostname"] = host_url;
ros::init(remappings,"qt_gui");
//檢查master是否存在,下面內容和上一個初始化函數一樣
if ( ! ros::master::check() ) {
return false;
}
ros::start(); // explicitly needed since our nodehandle is going out of scope.
ros::NodeHandle n;
// Add your ros communications here.
chatter_publisher = n.advertise<std_msgs::String>("chatter", 1000);
start();
return true;
}
//線程主函數。類比main
void QNode::run() {
ros::Rate loop_rate(1);//循環速率
int count = 0;
while ( ros::ok() ) {
//節點工作內容
std_msgs::String msg;
std::stringstream ss;
ss << "hello world " << count;
msg.data = ss.str();
chatter_publisher.publish(msg);
log(Info,std::string("I sent: ")+msg.data);
//節點循環
ros::spinOnce();
loop_rate.sleep();
++count;
}
std::cout << "Ros shutdown, proceeding to close the gui." << std::endl;
Q_EMIT rosShutdown(); // 發送ros關閉的信號到主窗口,Qt特有通訊機制
}
//信息顯示
void QNode::log( const LogLevel &level, const std::string &msg) {
logging_model.insertRows(logging_model.rowCount(),1);
std::stringstream logging_model_msg;
switch ( level ) {
case(Debug) : {
ROS_DEBUG_STREAM(msg);
logging_model_msg << "[DEBUG] [" << ros::Time::now() << "]: " << msg;
break;
}
case(Info) : {
ROS_INFO_STREAM(msg);
logging_model_msg << "[INFO] [" << ros::Time::now() << "]: " << msg;
break;
}
case(Warn) : {
ROS_WARN_STREAM(msg);
logging_model_msg << "[INFO] [" << ros::Time::now() << "]: " << msg;
break;
}
case(Error) : {
ROS_ERROR_STREAM(msg);
logging_model_msg << "[ERROR] [" << ros::Time::now() << "]: " << msg;
break;
}
case(Fatal) : {
ROS_FATAL_STREAM(msg);
logging_model_msg << "[FATAL] [" << ros::Time::now() << "]: " << msg;
break;
}
}
QVariant new_row(QString(logging_model_msg.str().c_str()));
logging_model.setData(logging_model.index(logging_model.rowCount()-1),new_row);
Q_EMIT loggingUpdated(); // used to readjust the scrollbar
}
} // namespace qt_gui
二、main_window
main_window.hpp
主窗口GUI頭文件,繼承QMainWindow類,爲標準Qt文件。master的信息通過QSettings寫入ini文件和從ini文件中讀取。
#ifndef qt_gui_MAIN_WINDOW_H
#define qt_gui_MAIN_WINDOW_H
/*****************************************************************************
** Includes
*****************************************************************************/
#include <QtGui/QMainWindow>
#include "ui_main_window.h"
#include "qnode.hpp" //節點頭文件
/*****************************************************************************
** Namespace
*****************************************************************************/
namespace qt_gui {
/*****************************************************************************
** 繼承 MainWindow
*****************************************************************************/
class MainWindow : public QMainWindow {
Q_OBJECT
public:
MainWindow(int argc, char** argv, QWidget *parent = 0);
~MainWindow();
void ReadSettings(); // 啓動時讀取設置參數
void WriteSettings(); // 關閉時保存設置參數
void closeEvent(QCloseEvent *event); // 覆寫窗口關閉方式,截取窗口關閉動作進行進一步處理
void showNoMasterMessage();
public Q_SLOTS: //公共槽,qt信號機制
/******************************************
** 自動連接 (connectSlotsByName())
*******************************************/
//以下三個函數爲GUI按鈕動作函數
void on_actionAbout_triggered();
void on_button_connect_clicked(bool check );
void on_checkbox_use_environment_stateChanged(int state);
/******************************************
** 手動連接
*******************************************/
void updateLoggingView(); // 無法自動連接下手動連接
private:
Ui::MainWindowDesign ui;
QNode qnode; //節點類
};
} // namespace qt_gui
#endif // qt_gui_MAIN_WINDOW_H
main_window.cpp
主窗口GUI .c文件
#include <QtGui>
#include <QMessageBox>
#include <iostream>
#include "../include/qt_gui/main_window.hpp"
/*****************************************************************************
** Namespaces
*****************************************************************************/
namespace qt_gui {
using namespace Qt;
/*****************************************************************************
** MainWindow初始化函數
*****************************************************************************/
MainWindow::MainWindow(int argc, char** argv, QWidget *parent)
: QMainWindow(parent)
, qnode(argc,argv)
{
ui.setupUi(this); // 將按鍵動作信號與其對應槽進行連接
QObject::connect(ui.actionAbout_Qt, SIGNAL(triggered(bool)), qApp, SLOT(aboutQt())); // qApp 時應用的全局變量
//從ini文件中讀取設置參數
ReadSettings();
//GUI初始化
setWindowIcon(QIcon(":/images/icon.png"));//設置圖標
ui.tab_manager->setCurrentIndex(0); // 確保顯示第一個標籤
QObject::connect(&qnode, SIGNAL(rosShutdown()), this, SLOT(close()));//連接qnode信號和close函數,確保ros被關閉時關閉該GUI。
/*********************
** 記錄
**********************/
ui.view_logging->setModel(qnode.loggingModel());
QObject::connect(&qnode, SIGNAL(loggingUpdated()), this, SLOT(updateLoggingView()));
/*********************
** 自動啓動
**********************/
if ( ui.checkbox_remember_settings->isChecked() ) {
on_button_connect_clicked(true);
}
}
MainWindow::~MainWindow() {}
/*****************************************************************************
** 自動啓動,若無法連接到輸入的Master,顯示錯誤信息,並關閉窗口
*****************************************************************************/
void MainWindow::showNoMasterMessage() {
QMessageBox msgBox;
msgBox.setText("Couldn't find the ros master.");
msgBox.exec();
close();
}
/*
當按鈕button_connect被點擊,獲取其狀態check(按下和彈起)
*/
void MainWindow::on_button_connect_clicked(bool check ) {
if ( ui.checkbox_use_environment->isChecked() ) {
if ( !qnode.init() ) {
showNoMasterMessage();
} else {
ui.button_connect->setEnabled(false);
}
} else {
if ( ! qnode.init(ui.line_edit_master->text().toStdString(),
ui.line_edit_host->text().toStdString()) ) {
showNoMasterMessage();
} else {
ui.button_connect->setEnabled(false);
ui.line_edit_master->setReadOnly(true);
ui.line_edit_host->setReadOnly(true);
ui.line_edit_topic->setReadOnly(true);
}
}
}
void MainWindow::on_checkbox_use_environment_stateChanged(int state) {
bool enabled;
if ( state == 0 ) {
enabled = true;
} else {
enabled = false;
}
ui.line_edit_master->setEnabled(enabled);
ui.line_edit_host->setEnabled(enabled);
//ui.line_edit_topic->setEnabled(enabled);
}
/*****************************************************************************
** 手動連接到Master
*****************************************************************************/
/*
當獲得新的數據,將舊的數據下移,保證最新數據再最上方。
*/
void MainWindow::updateLoggingView() {
ui.view_logging->scrollToBottom();
}
/*****************************************************************************
** Implementation [Menu]
*****************************************************************************/
void MainWindow::on_actionAbout_triggered() {
QMessageBox::about(this, tr("About ..."),tr("<h2>PACKAGE_NAME Test Program 0.10</h2><p>Copyright Yujin Robot</p><p>This package needs an about description.</p>"));
}
/*****************************************************************************
** 配置參數的寫入和讀取
*****************************************************************************/
void MainWindow::ReadSettings() {
QSettings settings("Qt-Ros Package", "qt_gui");
restoreGeometry(settings.value("geometry").toByteArray());
restoreState(settings.value("windowState").toByteArray());
QString master_url = settings.value("master_url",QString("http://192.168.1.2:11311/")).toString();
QString host_url = settings.value("host_url", QString("192.168.1.3")).toString();
//QString topic_name = settings.value("topic_name", QString("/chatter")).toString();
ui.line_edit_master->setText(master_url);
ui.line_edit_host->setText(host_url);
//ui.line_edit_topic->setText(topic_name);
bool remember = settings.value("remember_settings", false).toBool();
ui.checkbox_remember_settings->setChecked(remember);
bool checked = settings.value("use_environment_variables", false).toBool();
ui.checkbox_use_environment->setChecked(checked);
if ( checked ) {
ui.line_edit_master->setEnabled(false);
ui.line_edit_host->setEnabled(false);
//ui.line_edit_topic->setEnabled(false);
}
}
void MainWindow::WriteSettings() {
QSettings settings("Qt-Ros Package", "qt_gui");
settings.setValue("master_url",ui.line_edit_master->text());
settings.setValue("host_url",ui.line_edit_host->text());
//settings.setValue("topic_name",ui.line_edit_topic->text());
settings.setValue("use_environment_variables",QVariant(ui.checkbox_use_environment->isChecked()));
settings.setValue("geometry", saveGeometry());
settings.setValue("windowState", saveState());
settings.setValue("remember_settings",QVariant(ui.checkbox_remember_settings->isChecked()));
}
//截獲關閉函數,先寫入設置參數再關閉窗口
void MainWindow::closeEvent(QCloseEvent *event)
{
WriteSettings();
QMainWindow::closeEvent(event);
}
} // namespace qt_gui
三、main
main.cpp
#include <QtGui>
#include <QApplication>
#include "../include/qt_gui/main_window.hpp"
/*****************************************************************************
** Main
*****************************************************************************/
int main(int argc, char **argv) {
/*********************
** Qt
**********************/
QApplication app(argc, argv);
qt_gui::MainWindow w(argc,argv);
w.show();
app.connect(&app, SIGNAL(lastWindowClosed()), &app, SLOT(quit()));
int result = app.exec();
return result;
}