我是靠谱客的博主 英勇马里奥,最近开发中收集的这篇文章主要介绍ROS下基于Qt的人机交互开发(四)在Qt中发布和订阅话题前言一、创建节点二、发布话题三、订阅话题四、键盘控制五、运行终端命令六、案例源码,觉得挺不错的,现在分享给大家,希望可以做个参考。

概述

目录

前言

一、创建节点

二、发布话题

三、订阅话题

四、键盘控制

五、运行终端命令

六、案例源码


前言

本案例包括

  • 在Qt中创建节点
  • 发布话题控制海龟移动
  • 订阅话题实时显示海龟位置。
  • 键盘控制实现
  • qt中运行终端命令

本案例是在ros中创建的qt功能包的基础进行的,在ros中创建qt功能包可以参考下文

ROS下基于Qt的人机交互开发(一)开发环境搭建icon-default.png?t=M666https://blog.csdn.net/m0_56451176/article/details/126122360?spm=1001.2014.3001.5502


一、创建节点

bool QNode::init() 
{
    //初始化ROS节点“ros_qt_demo”
	ros::init(init_argc,init_argv,"ros_qt_demo");
    //检测ROS节点是否打开
	if ( ! ros::master::check() ) 
    {
		return false;
	}
    //启动
	ros::start(); 
    //创建句柄
	ros::NodeHandle n;
	//创建发布者
    chatter_publisher = n.advertise<std_msgs::String>("chatter", 1000);
    //调用run()
	start();
	return true;
}

注:这个qt功能包自带的init有两种形式,两种init函数中内容相似 


二、发布话题

命令行发布话题请参考:

ROS学习(四)--1.发布者与订阅者案例icon-default.png?t=M666https://blog.csdn.net/m0_56451176/article/details/126222244?spm=1001.2014.3001.5502

1.在头文件中创建发布者对象turtle_vel_pub;

ros::Publisher turtle_vel_pub;

2.在源文件中定义发布者(init()中定义,即上文发布者所在函数中)

turtle_vel_pub = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 10);

3.在run()函数中发布消息

void QNode::run() {
	ros::Rate loop_rate(1);
	int count = 0;
	while ( ros::ok() )
    {
        geometry_msgs::Twist vel_msg;
        vel_msg.linear.x = linevelocity*0.01;
        vel_msg.angular.z = angular*0.01;
        // 发布消息
        turtle_vel_pub.publish(vel_msg);

		ros::spinOnce();
		loop_rate.sleep();
		++count;
	}
	std::cout << "Ros shutdown, proceeding to close the gui." << std::endl;
	Q_EMIT rosShutdown(); // used to signal the gui for a shutdown (useful to roslaunch)
}

在while ( ros::ok() )循环中添加要发布的信息

geometry_msgs::Twist vel_msg;
vel_msg.linear.x = linevelocity*0.01;
vel_msg.angular.z = angular*0.01;

本案例定义了要发布的信息为:海龟x方向线速度和z方向角速度

发布话题:

 turtle_vel_pub.publish(vel_msg);

总结:

  1. 创建发布者
  2. 定义消息类型和内容
  3. 发布消息

三、订阅话题

 命令行订阅话题请参考:

ROS学习(四)--1.发布者与订阅者案例icon-default.png?t=M666https://blog.csdn.net/m0_56451176/article/details/126222244?spm=1001.2014.3001.5502

1.在头文件中创建发布者对象pose_sub;

ros::Subscriber pose_sub;

2.在源文件中定义发布者(init()中定义,即上文发布者所在函数中)

pose_sub = n.subscribe("/turtle1/pose", 10, &QNode::poseCallback,this);

注:此处与命令行方式的定义有所不同,

  1. 回调函数前要加上“&”和“类名”
  2. 回调函数后面再加上“this”

3.创建回调函数

void QNode::poseCallback(const turtlesim::Pose::ConstPtr& msg)
{
    // 将接收到的消息打印出来
    std::stringstream ss;
    ss<<"x:"<<msg->x<<"  y:"<<msg->y;
    log(Info,"Turtle pose:"+ss.str());
}

回调函数中对话题进行处理,通过自带的log函数输出

总结:

  1. 创建订阅者
  2. 定义回调函数

四、键盘控制

void ros_qt_demo::MainWindow::on_pushButton_W_pressed()
{
    int x=ui.label_6->text().toInt();
    if(x==0) x=20;
    ui.horizontalSlider->setValue(x);
}


void ros_qt_demo::MainWindow::on_pushButton_W_released()
{
    ui.horizontalSlider->setValue(0);
}

void ros_qt_demo::MainWindow::on_pushButton_S_pressed()
{
    int x=ui.label_6->text().toInt();
    x=0-x;
    if(x==0) x=-50;
    ui.horizontalSlider->setValue(x);   
}

void ros_qt_demo::MainWindow::on_pushButton_S_released()
{   
  ui.horizontalSlider->setValue(0);
}

void ros_qt_demo::MainWindow::on_pushButton_A_pressed()
{
    int x=ui.label_7->text().toInt();
    if(x==0) x=50;
    ui.horizontalSlider_2->setValue(x);
}

void ros_qt_demo::MainWindow::on_pushButton_A_released()
{
    ui.horizontalSlider_2->setValue(0);
}

void ros_qt_demo::MainWindow::on_pushButton_D_pressed()
{
    int x=ui.label_7->text().toInt();
    x=0-x;
    if(x==0) x=-50;
    ui.horizontalSlider_2->setValue(x);
}

void ros_qt_demo::MainWindow::on_pushButton_D_released()
{
    ui.horizontalSlider_2->setValue(0);
}

由于发布话题和ui分别写在两个不同的类中,需要通过信号与槽机制建立连接。

1.main_window.hpp

signals:
    void getlinevelocity(int velocity);
    void getlangular(int velocity);

2.qnode.hpp

  public slots:
    void on_getlinevelocity(int velocity);
    void on_getlangular(int velocity);

3.连接

connect(this,SIGNAL(getlinevelocity(int)),&qnode,SLOT(on_getlinevelocity(int)));
connect(this,SIGNAL(getlangular(int)),&qnode,SLOT(on_getlangular(int)));


五、运行终端命令

void ros_qt_demo::MainWindow::on_pushButton_3_clicked()
{
    QProcess *process=new QProcess;
    //打开终端
    process->start("bash");
    //写入命令
    process->write(ui.textEdit->toPlainText().toLocal8Bit()+'n');
    ui.textBrowser->append(process->readAll().data());
}

 注:process->write(ui.textEdit->toPlainText().toLocal8Bit()+'n');中‘n’不可省略


六、案例源码

1.main_window.hpp

/**
 * @file /include/ros_qt_demo/main_window.hpp
 *
 * @brief Qt based gui for ros_qt_demo.
 *
 * @date November 2010
 **/
#ifndef ros_qt_demo_MAIN_WINDOW_H
#define ros_qt_demo_MAIN_WINDOW_H

/*****************************************************************************
** Includes
*****************************************************************************/

#include <QtWidgets/QMainWindow>
#include "ui_main_window.h"
#include "qnode.hpp"

/*****************************************************************************
** Namespace
*****************************************************************************/

namespace ros_qt_demo {

/*****************************************************************************
** Interface [MainWindow]
*****************************************************************************/
/**
 * @brief Qt central, all operations relating to the view part here.
 */
class MainWindow : public QMainWindow {
Q_OBJECT

signals:
    void getlinevelocity(int velocity);
    void getlangular(int velocity);

public:
	MainWindow(int argc, char** argv, QWidget *parent = 0);
	~MainWindow();

	void ReadSettings(); // Load up qt program settings at startup
	void WriteSettings(); // Save qt program settings when closing

	void closeEvent(QCloseEvent *event); // Overloaded function
	void showNoMasterMessage();

public Q_SLOTS:
	/******************************************
	** Auto-connections (connectSlotsByName())
	*******************************************/
	void on_actionAbout_triggered();
	void on_button_connect_clicked(bool check );
	void on_checkbox_use_environment_stateChanged(int state);

    /******************************************
    ** Manual connections
    *******************************************/
    void updateLoggingView(); // no idea why this can't connect automatically




private slots:
    void on_horizontalSlider_valueChanged(int value);

    void on_horizontalSlider_2_valueChanged(int value);

    void on_pushButton_clicked();

    void on_pushButton_2_clicked();


    void on_pushButton_W_pressed();

    void on_pushButton_W_released();

    void on_pushButton_S_pressed();

    void on_pushButton_S_released();

    void on_pushButton_A_pressed();

    void on_pushButton_A_released();

    void on_pushButton_D_pressed();

    void on_pushButton_D_released();

    void on_pushButton_3_clicked();

private:
	Ui::MainWindowDesign ui;
	QNode qnode;
};

}  // namespace ros_qt_demo

#endif // ros_qt_demo_MAIN_WINDOW_H

2.main_window.cpp

/**
 * @file /src/main_window.cpp
 *
 * @brief Implementation for the qt gui.
 *
 * @date February 2011
 **/
/*****************************************************************************
** Includes
*****************************************************************************/

#include <QtGui>
#include <QMessageBox>
#include <iostream>
#include "../include/ros_qt_demo/main_window.hpp"
#include<qprocess.h>

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ros_qt_demo {

using namespace Qt;

/*****************************************************************************
** Implementation [MainWindow]
*****************************************************************************/

MainWindow::MainWindow(int argc, char** argv, QWidget *parent)
	: QMainWindow(parent)
	, qnode(argc,argv)
{
	ui.setupUi(this); // Calling this incidentally connects all ui's triggers to on_...() callbacks in this class.
    QObject::connect(ui.actionAbout_Qt, SIGNAL(triggered(bool)), qApp, SLOT(aboutQt())); // qApp is a global variable for the application

    ReadSettings();
	setWindowIcon(QIcon(":/images/icon.png"));
	ui.tab_manager->setCurrentIndex(0); // ensure the first tab is showing - qt-designer should have this already hardwired, but often loses it (settings?).
    QObject::connect(&qnode, SIGNAL(rosShutdown()), this, SLOT(close()));

	/*********************
	** Logging
	**********************/
	ui.view_logging->setModel(qnode.loggingModel());
    QObject::connect(&qnode, SIGNAL(loggingUpdated()), this, SLOT(updateLoggingView()));

    /*********************
    ** Auto Start
    **********************/
    if ( ui.checkbox_remember_settings->isChecked() ) {
        on_button_connect_clicked(true);
    }

    connect(this,SIGNAL(getlinevelocity(int)),&qnode,SLOT(on_getlinevelocity(int)));
    connect(this,SIGNAL(getlangular(int)),&qnode,SLOT(on_getlangular(int)));
}


MainWindow::~MainWindow() {}

/*****************************************************************************
** Implementation [Slots]
*****************************************************************************/

void MainWindow::showNoMasterMessage() {
	QMessageBox msgBox;
	msgBox.setText("Couldn't find the ros master.");
	msgBox.exec();
    close();
}

/*
 * These triggers whenever the button is clicked, regardless of whether it
 * is already checked or not.
 */

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);
}

/*****************************************************************************
** Implemenation [Slots][manually connected]
*****************************************************************************/

/**
 * This function is signalled by the underlying model. When the model changes,
 * this will drop the cursor down to the last line in the QListview to ensure
 * the user can always see the latest log message.
 */
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>"));
}

/*****************************************************************************
** Implementation [Configuration]
*****************************************************************************/

void MainWindow::ReadSettings() {
    QSettings settings("Qt-Ros Package", "ros_qt_demo");
    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", "ros_qt_demo");
    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 ros_qt_demo


void ros_qt_demo::MainWindow::on_horizontalSlider_valueChanged(int value)
{
    ui.label_6->setText(QString::number(value));
    emit getlinevelocity(value);
}

void ros_qt_demo::MainWindow::on_horizontalSlider_2_valueChanged(int value)
{
    ui.label_7->setText(QString::number(value));
    emit getlangular(value);

}

void ros_qt_demo::MainWindow::on_pushButton_clicked()
{
    ui.horizontalSlider->setValue(0);
}

void ros_qt_demo::MainWindow::on_pushButton_2_clicked()
{
    ui.horizontalSlider_2->setValue(0);
}


void ros_qt_demo::MainWindow::on_pushButton_W_pressed()
{
    int x=ui.label_6->text().toInt();
    if(x==0) x=20;
    ui.horizontalSlider->setValue(x);

}


void ros_qt_demo::MainWindow::on_pushButton_W_released()
{
    ui.horizontalSlider->setValue(0);
}

void ros_qt_demo::MainWindow::on_pushButton_S_pressed()
{
    int x=ui.label_6->text().toInt();
    x=0-x;
    if(x==0) x=-50;
    ui.horizontalSlider->setValue(x);   
}

void ros_qt_demo::MainWindow::on_pushButton_S_released()
{   
  ui.horizontalSlider->setValue(0);
}

void ros_qt_demo::MainWindow::on_pushButton_A_pressed()
{
    int x=ui.label_7->text().toInt();
    if(x==0) x=50;
    ui.horizontalSlider_2->setValue(x);

}

void ros_qt_demo::MainWindow::on_pushButton_A_released()
{
    ui.horizontalSlider_2->setValue(0);
}

void ros_qt_demo::MainWindow::on_pushButton_D_pressed()
{
    int x=ui.label_7->text().toInt();
    x=0-x;
    if(x==0) x=-50;
    ui.horizontalSlider_2->setValue(x);

}

void ros_qt_demo::MainWindow::on_pushButton_D_released()
{
    ui.horizontalSlider_2->setValue(0);
}

void ros_qt_demo::MainWindow::on_pushButton_3_clicked()
{
    QProcess *process=new QProcess;
    //打开终端
    process->start("bash");
    //写入命令
    process->write(ui.textEdit->toPlainText().toLocal8Bit()+'n');
    ui.textBrowser->append(process->readAll().data());
}

3.qnode.hpp

/**
 * @file /include/ros_qt_demo/qnode.hpp
 *
 * @brief Communications central!
 *
 * @date February 2011
 **/
/*****************************************************************************
** Ifdefs
*****************************************************************************/

#ifndef ros_qt_demo_QNODE_HPP_
#define ros_qt_demo_QNODE_HPP_

/*****************************************************************************
** Includes
*****************************************************************************/

// To workaround boost/qt4 problems that won't be bugfixed. Refer to
//    https://bugreports.qt.io/browse/QTBUG-22829
#ifndef Q_MOC_RUN
#include <ros/ros.h>
#endif
#include <string>
#include <QThread>
#include <QStringListModel>

#include <geometry_msgs/Twist.h>
#include "turtlesim/Pose.h"

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ros_qt_demo {

/*****************************************************************************
** Class
*****************************************************************************/

class QNode : public QThread {
    Q_OBJECT
public:
	QNode(int argc, char** argv );
	virtual ~QNode();
	bool init();
	bool init(const std::string &master_url, const std::string &host_url);
	void run();

	/*********************
	** Logging
	**********************/
	enum LogLevel {
	         Debug,
	         Info,
	         Warn,
	         Error,
	         Fatal
	 };

	QStringListModel* loggingModel() { return &logging_model; }
	void log( const LogLevel &level, const std::string &msg);

    int linevelocity=0;
    int angular=0;

Q_SIGNALS:
	void loggingUpdated();
    void rosShutdown();

private:
	int init_argc;
	char** init_argv;
    //ros::Publisher chatter_publisher;
        ros::Publisher turtle_vel_pub;
        ros::Subscriber pose_sub;
        void poseCallback(const turtlesim::Pose::ConstPtr& msg);

    QStringListModel logging_model;

  public slots:
    void on_getlinevelocity(int velocity);
    void on_getlangular(int velocity);

};

}  // namespace ros_qt_demo

#endif /* ros_qt_demo_QNODE_HPP_ */

4.qnode.cpp

/**
 * @file /src/qnode.cpp
 *
 * @brief Ros communication central!
 *
 * @date February 2011
 **/

/*****************************************************************************
** Includes
*****************************************************************************/

#include <ros/ros.h>
#include <ros/network.h>
#include <string>
#include <std_msgs/String.h>
#include <sstream>
#include "../include/ros_qt_demo/qnode.hpp"
#include<qdebug.h>

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ros_qt_demo {

/*****************************************************************************
** Implementation
*****************************************************************************/

QNode::QNode(int argc, char** argv ) :
	init_argc(argc),
	init_argv(argv)
	{}

QNode::~QNode() {
    if(ros::isStarted()) {
      ros::shutdown(); // explicitly needed since we use ros::start();
      ros::waitForShutdown();
    }
	wait();
}

bool QNode::init() 
{
    //初始化ROS节点“ros_qt_demo”
	ros::init(init_argc,init_argv,"ros_qt_demo");
    //检测ROS节点是否打开
	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);
    turtle_vel_pub = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 10);
    pose_sub = n.subscribe("/turtle1/pose", 10, &QNode::poseCallback,this);
	//调用run()
    start();
	return true;
}

bool QNode::init(const std::string &master_url, const std::string &host_url) {
	std::map<std::string,std::string> remappings;
	remappings["__master"] = master_url;
	remappings["__hostname"] = host_url;
	ros::init(remappings,"ros_qt_demo");
	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);
    turtle_vel_pub = n.advertise<geometry_msgs::Twist>("/turtle1/cmd_vel", 10);
    pose_sub = n.subscribe("/turtle1/pose", 10, &QNode::poseCallback,this);
	start();
	return true;
}

void QNode::poseCallback(const turtlesim::Pose::ConstPtr& msg)
{
    // 将接收到的消息打印出来
    std::stringstream ss;
    ss<<"x:"<<msg->x<<"  y:"<<msg->y;
    log(Info,"Turtle pose:"+ss.str());

}

void QNode::run() {
	ros::Rate loop_rate(1);
	int count = 0;
	while ( ros::ok() ) {


        geometry_msgs::Twist vel_msg;
        vel_msg.linear.x = linevelocity*0.01;
        vel_msg.angular.z = angular*0.01;

        // 发布消息
        turtle_vel_pub.publish(vel_msg);



//		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(); // used to signal the gui for a shutdown (useful to roslaunch)
}

void QNode::on_getlinevelocity(int velocity)
{
    linevelocity=velocity;
}
 void QNode::on_getlangular(int velocity)
 {
     angular=velocity;
 }

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 ros_qt_demo

最后

以上就是英勇马里奥为你收集整理的ROS下基于Qt的人机交互开发(四)在Qt中发布和订阅话题前言一、创建节点二、发布话题三、订阅话题四、键盘控制五、运行终端命令六、案例源码的全部内容,希望文章能够帮你解决ROS下基于Qt的人机交互开发(四)在Qt中发布和订阅话题前言一、创建节点二、发布话题三、订阅话题四、键盘控制五、运行终端命令六、案例源码所遇到的程序开发问题。

如果觉得靠谱客网站的内容还不错,欢迎将靠谱客网站推荐给程序员好友。

本图文内容来源于网友提供,作为学习参考使用,或来自网络收集整理,版权属于原作者所有。
点赞(49)

评论列表共有 0 条评论

立即
投稿
返回
顶部