• 欢迎访问开心洋葱网站,在线教程,推荐使用最新版火狐浏览器和Chrome浏览器访问本网站,欢迎加入开心洋葱 QQ群
  • 为方便开心洋葱网用户,开心洋葱官网已经开启复制功能!
  • 欢迎访问开心洋葱网站,手机也能访问哦~欢迎加入开心洋葱多维思维学习平台 QQ群
  • 如果您觉得本站非常有看点,那么赶紧使用Ctrl+D 收藏开心洋葱吧~~~~~~~~~~~~~!
  • 由于近期流量激增,小站的ECS没能经的起亲们的访问,本站依然没有盈利,如果各位看如果觉着文字不错,还请看官给小站打个赏~~~~~~~~~~~~~!

ROS Qt5 librviz人机交互界面开发三(实现控制机器人速度与方向)

人工智能 蒋程扬 2235次浏览 0个评论

我这里主要就是参考teleop_twist_keyboard项目的源代码,移植到自己程序

一,首先在ui界面添加按钮(注意按钮上显示的文字):

在这里插入图片描述

 

同时在ui界面设置每个按钮的shortcut(热键),就能实现键盘控制:

在这里插入图片描述

 

二,关联这些按钮的点击事件到同一槽函数

 

//绑定速度控制按钮
connect(ui.pushButton_i,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_u,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_o,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_j,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_l,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_m,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_back,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));
connect(ui.pushButton_backr,SIGNAL(clicked()),this,SLOT(slot_cmd_control()));

 

槽函数:

#ifndef CCTRLDASHBOARD_H
#define CCTRLDASHBOARD_H

#include <QWidget>

class CCtrlDashBoard : public QWidget
{
	Q_OBJECT
public:
	enum StyleType {
		ST_DEFAULT=0,//速度控制相关按钮处理槽函数
		void MainWindow::slot_cmd_control()
		{

			QPushButton* btn=qobject_cast<QPushButton*>(sender());
			char key=btn->text().toStdString()[0];
//速度
			float liner=ui.horizontalSlider_linear->value()*0.01;
			float turn=ui.horizontalSlider_raw->value()*0.01;
			bool is_all=ui.checkBox_use_all->isChecked();
			switch (key) {
			case 'u':
				qnode.move_base(is_all?'U':'u',liner,turn);
				break;
			case 'i':
				qnode.move_base(is_all?'I':'i',liner,turn);
				break;
			case 'o':
				qnode.move_base(is_all?'O':'o',liner,turn);
				break;
			case 'j':
				qnode.move_base(is_all?'J':'j',liner,turn);
				break;
			case 'l':
				qnode.move_base(is_all?'L':'l',liner,turn);
				break;
			case 'm':
				qnode.move_base(is_all?'M':'m',liner,turn);
				break;
			case ',':
				qnode.move_base(is_all?'<':',',liner,turn);
				break;
			case '.':
				qnode.move_base(is_all?'>':'.',liner,turn);
				break;
			}
		}
		ST_ARCBAR
	};
	explicit CCtrlDashBoard(QWidget *parent = nullptr, StyleType type=ST_DEFAULT);

	void setValue(qreal value)
	{
		m_DashValue = value;
		update();
	}
	void setBackGroundColor(QColor color)
	{
		m_BgColor=color;
		update();
	}
	void setFrontColor(QColor color)
	{
		m_FrontColor=color;
		update();
	}
	void setBorderColor(QColor color)
	{
		m_BorderColor=color;
		update();
	}
	void setUnitString(QString str)
	{
		m_StrUnit=str;
		update();
	}

	void drawBackGround(QPainter *painter, qreal hlafWidth);
	void drawScaleDials(QPainter *painter, qreal hlafWidth);
	void drawIndicator(QPainter *painter, qreal hlafWidth);
	void drawIndicatorBar(QPainter *painter, qreal hlafWidth);
signals:

public slots:
protected:
	virtual void paintEvent(QPaintEvent * event);

private:
	int m_StartAngle;
	int m_EndAngle;
	int m_StyleType;

	qreal m_LineLength;
	qreal m_DashValue;
	qreal m_MaxValue;
	qreal m_MinValue;
	qreal m_DashNum;

	QColor m_BgColor;
	QColor m_FrontColor;
	QColor m_BorderColor;
	QString m_StrUnit;

	qreal m_MaxBorderRadius;
	qreal m_MinBorderRadius;
	qreal m_DialsRadius;
};

#endif // CCTRLDASHBOARD_H

 

创建发布者:

//速度控制话题 
cmd_pub = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);

 

qnode.move_base:

//发布机器人速度控制
void QNode::move_base(char k,float speed_linear,float speed_trun)
{
	std::map<char, std::vector<float>> moveBindings {
		{'i', {1, 0, 0, 0}},
		{'o', {1, 0, 0, -1}},
		{'j', {0, 0, 0, 1}},
		{'l', {0, 0, 0, -1}},
		{'u', {1, 0, 0, 1}},
		{',', {-1, 0, 0, 0}},
		{'.', {-1, 0, 0, 1}},
		{'m', {-1, 0, 0, -1}},
		{'O', {1, -1, 0, 0}},
		{'I', {1, 0, 0, 0}},
		{'J', {0, 1, 0, 0}},
		{'L', {0, -1, 0, 0}},
		{'U', {1, 1, 0, 0}},
		{'<', {-1, 0, 0, 0}},
		{'>', {-1, -1, 0, 0}},
		{'M', {-1, 1, 0, 0}},
		{'t', {0, 0, 1, 0}},
		{'b', {0, 0, -1, 0}},
		{'k', {0, 0, 0, 0}},
		{'K', {0, 0, 0, 0}}
	};
	char key=k;
//计算是往哪个方向
	float x = moveBindings[key][0];
	float y = moveBindings[key][1];
	float z = moveBindings[key][2];
	float th = moveBindings[key][3];
//计算线速度和角速度
	float speed = speed_linear;
	float turn = speed_trun;
// Update the Twist message
	geometry_msgs::Twist twist;
	twist.linear.x = x * speed;
	twist.linear.y = y * speed;
	twist.linear.z = z * speed;

	twist.angular.x = 0;
	twist.angular.y = 0;
	twist.angular.z = th * turn;

// Publish it and resolve any remaining callbacks
	cmd_pub.publish(twist);
	ros::spinOnce();

}

 

三,完整开源项目

在我自己学习的过程中目前发现没有相关类似完整开源项目,为了帮助其他人少走弯路,我决定将自己的完整项目开源:
github

本人原博客地址:

csdn


开心洋葱 , 版权所有丨如未注明 , 均为原创丨未经授权请勿修改 , 转载请注明ROS Qt5 librviz人机交互界面开发三(实现控制机器人速度与方向)
喜欢 (0)

您必须 登录 才能发表评论!

加载中……