一、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;
}