Python写机器人上位机
- python界面设计插件
- Tkinter
- pyqt5
- pyqt5使用教程
- Qt Designer使用教程
- ROS通讯机制实现界面与下位机通讯
- 示例代码
python界面设计插件
Python写GUI的插件比较多,常用的有Tkinter、pyqt5,本将使用pyqt5写机器人的上位机。
Tkinter
Tkinter 是 Python 的标准 GUI 库,是Python推荐使用的界面创建工具,Python 使用 Tkinter 可以快速的创建 GUI 应用程序。由于 Tkinter 是内置到 python 的安装包中、只要安装好 Python 之后就能 import Tkinter 库、而且 IDLE 也是用 Tkinter 编写而成、对于简单的图形界面 Tkinter 还是能应付自如。
想更多了解Tkinter,可以参考https://www.runoob.com/python/python-gui-tkinter.html
pyqt5
pyqt5是非常优秀的工具,可以快速的开发出机器人的上位机,其与Qt Designer结合,实现界面与代码分离,通过调用界面函数实现相关功能。pyqt5是一套Python绑定Digia QT5应用的框架。它可用于Python 2和3。本教程使用Python 3。Qt库是最强大的GUI库之一。pyqt5做为Python的一个模块,它有620多个类和6000个函数和方法。这是一个跨平台的工具包,它可以运行在所有主要的操作系统,包括UNIX,Windows,Mac OS。pyqt5是双重许可。开发者可以在GPL和商业许可之间进行选择。
pyqt5使用教程
pyqt5主要功能模块如下:
QtCore:包含了核心的非GUI功能。此模块用于处理时间、文件和目录、各种数据类型、流、URL、MIME类型、线程或进程。
QtGui包含类窗口系统集成、事件处理、二维图形、基本成像、字体和文本。
qtwidgets模块包含创造经典桌面风格的用户界面提供了一套UI元素的类。
QtMultimedia包含的类来处理多媒体内容和API来访问相机和收音机的功能。
Qtbluetooth模块包含类的扫描设备和连接并与他们互动。描述模块包含了网络编程的类。这些类便于TCP和IP和UDP客户端和服务器的编码,使网络编程更容易和更便携。
Qtpositioning包含类的利用各种可能的来源,确定位置,包括卫星、Wi-Fi、或一个文本文件。
Enginio模块实现了客户端库访问Qt云服务托管的应用程序运行时。
Qtwebsockets模块包含实现WebSocket协议类。
QtWebKit包含一个基于Webkit2图书馆Web浏览器实现类。
Qtwebkitwidgets包含的类的基础webkit1一用于qtwidgets应用Web浏览器的实现。
QtXml包含与XML文件的类。这个模块为SAX和DOM API提供了实现。
QtSvg模块提供了显示SVG文件内容的类。可伸缩矢量图形(SVG)是一种描述二维图形和图形应用的语言。
QtSql模块提供操作数据库的类。
QtTest包含的功能,使pyqt5应用程序的单元测试
pyqt5基本功能很容易学懂,建议学习中文教程:pyqt5中文教程
Qt Designer使用教程
pyqt5可以调用函数直接创建界面、标签、按钮等,但是代码创建过程中,无法可视化调整框件的位置,Qt Designer可以实现可视化创建界面。
Qt Designer界面如下图所示:
左侧是标签、按钮等控件和布局等,右侧是对象查看器,可以在上面修界面上的控件属性,中间的白版是最终的界面。设计好的界面保存为_.ui文件,Python虽然可以直接使用_.ui文件,但是建议通过PyUIC转换为_.py文件使用,当然该文件也可以直接调用函数编写(大佬级)。
学习Qt Designer建议参考:
ROS通讯机制实现界面与下位机通讯
ROS中最常用的通讯方式话题,其次是服务,最后是动作,通过话题可以接收机器人反馈的关节角度和六维力矩。
当界面设计好后,通过内部的代码使界面具有相应的功能,如下图展示的关节空间规划及用pyqtgraph绘制规划号的数据图。
当点击开始时,通过话题发送规划好的关节角到gazebo或下位机,通过定时器QTimer定时刷新绘图框,实现关节角的在线和关节速度实时显示,如下所示。
示例代码
主函数:gui_demo.py
#!/usr/bin/python
#-*-coding:utf-8-*-
#本文档用于GUI开发界面函数:示例代码
#程序员:陈永*
#版权:哈尔滨工业大学(深圳)
#日期:2020.12.21
#系统函数
import numpy as np
#pyqt5函数
from PyQt5.QtWidgets import *
from PyQt5.QtGui import *
from PyQt5.QtCore import *
#ros相关模块
import rospy
from std_msgs.msg import Float64MultiArray
from sensor_msgs.msg import JointState
from geometry_msgs.msg import WrenchStamped
from robot_msg.srv import *
#绘图函数
import pyqtgraph as pg
#线程函数
import threading
#界面函数
from main_windon import Ui_MainWindow
from armc_form1 import Ui_ArmcForm1
#自定义文件
import gui_function_demo as gf
#**********************************主窗口***************************************#
class MainWindow(QMainWindow, Ui_MainWindow):
#建立全局变量
state_qq_list = list(np.zeros([1000, 7]))
state_f_list = list(np.zeros([1000, 6]))
state_t_list = list(np.zeros(1000))
state_t = 0
def __init__(self, parent=None):
super(MainWindow, self).__init__(parent)
self.T = 0.01
self.run_flag = True # 开始或停止标签
self.arm_flag = False
self.real_flag = False
self.sub_force_path = "/ft_sensor_topic"
self.sub_pos_path = "/joint_states"
self.pub_path = "/armc/joint_positions_controller/command"
self.n = 7 # 机械臂关节数
self.setupUi(self)
self.initUI()
def initUI(self):
# ======================菜单栏功能模块=======================#
#创建菜单
menubar = self.menuBar()
fileMenu = menubar.addMenu('&文件')
armcMenu = menubar.addMenu('&自制Armc')
#-------------------文件菜单-------------------#
# 中打开文件操作
openFile = QAction(QIcon('exit.png'), '打开', self)
openFile.setShortcut('Ctrl+o')
openFile.setStatusTip('打开文件')
openFile.triggered.connect(self.fileOpen)
fileMenu.addAction(openFile)
#文件菜单中关闭操作
exitAction = QAction(QIcon('exit.png'), '&退出', self)
exitAction.setShortcut('Ctrl+q')
exitAction.setStatusTip('退出软件')
exitAction.triggered.connect(qApp.quit)
fileMenu.addAction(exitAction)
# -------------------Armc菜单-------------------#
#armc机械臂关节空间规划
openArmc1 = QAction(QIcon('exit.png'), '关节控制', self)
openArmc1.setShortcut('Ctrl+c')
openArmc1.setStatusTip('自制机械臂关节空间规划和控制')
openArmc1.triggered.connect(self.gotoArmc1)
armcMenu.addAction(openArmc1)
# =======================绘图相关设置=======================#
self.p1, self.p2 = self.set_graph_ui() # 设置绘图窗口
# =======================按钮功能模块=======================#
self.button_begin.clicked.connect(self.begin_function)
self.button_stop.clicked.connect(self.stop)
self.button_wish_pos.clicked.connect(self.read_wish_pos)
self.button_receive.clicked.connect(self.run_topic)
self.button_plan.clicked.connect(self.plan)
self.checkBox_gazebo.stateChanged.connect(self.gazebo_or_real)
#打开文件的地址和内容
def fileOpen(self):
#打开文件操作
fname = QFileDialog.getOpenFileName(self, 'Open file', '/home')
if fname[0]:
f = open(fname[0], 'r')
self.filedir = fname[0]
with f:
data = f.read()
self.pubdata = data
self.textEdit.setText(data)
#===============按钮功能模块相关函数================#
#采用pyqtgraph绘制曲线,添加画板
def set_graph_ui(self):
pg.setConfigOptions(antialias=True) # pg全局变量设置函数,antialias=True开启曲线抗锯齿
win1 = pg.GraphicsLayoutWidget() # 创建pg layout,可实现数据界面布局自动管理
win2 = pg.GraphicsLayoutWidget()
# pg绘图窗口可以作为一个widget添加到GUI中的graph_layout,当然也可以添加到Qt其他所有的容器中
self.horizontalLayout_1.addWidget(win1)
self.horizontalLayout_2.addWidget(win2)
p1 = win1.addPlot(title="joint pos") # 添加第一个绘图窗口
p1.setLabel('left', text='pos/rad', color='#ffffff') # y轴设置函数
p1.showGrid(x=True, y=True) # 栅格设置函数
p1.setLogMode(x=False, y=False) # False代表线性坐标轴,True代表对数坐标轴
p1.setLabel('bottom', text='time', units='s') # x轴设置函数
p1.addLegend(size=(50, 30)) # 可选择是否添加legend
p2 = win2.addPlot(title="force") # 添加第一个绘图窗口
p2.setLabel('left', text='force/N', color='#ffffff') # y轴设置函数
p2.showGrid(x=True, y=True) # 栅格设置函数
p2.setLogMode(x=False, y=False) # False代表线性坐标轴,True代表对数坐标轴
p2.setLabel('bottom', text='time', units='s') # x轴设置函数
p2.addLegend(size=(50, 30))
return p1,p2
#绘画关节角和关节角速度曲线
def plot_joint(self, t1, qq, t2, f):
# 绘制位置图,表示颜色的单字符串(b,g,r,c,m,y,k,w)
self.p1.plot(t1, qq[:, 0], pen='b', name='qq1', clear=True)
self.p1.plot(t1, qq[:, 1], pen='g', name='qq2', clear=False)
self.p1.plot(t1, qq[:, 2], pen='r', name='qq3', clear=False)
self.p1.plot(t1, qq[:, 3], pen='c', name='qq4', clear=False)
self.p1.plot(t1, qq[:, 4], pen='m', name='qq5', clear=False)
self.p1.plot(t1, qq[:, 5], pen='y', name='qq6', clear=False)
self.p1.plot(t1, qq[:, 6], pen='w', name='qq7', clear=False)
# 绘制速度图
self.p2.plot(t2, f[:, 0], pen='b', name='F1', clear=True)
self.p2.plot(t2, f[:, 1], pen='g', name='F2', clear=False)
self.p2.plot(t2, f[:, 2], pen='r', name='F3', clear=False)
self.p2.plot(t2, f[:, 3], pen='c', name='F4', clear=False)
self.p2.plot(t2, f[:, 4], pen='m', name='F5', clear=False)
self.p2.plot(t2, f[:, 5], pen='y', name='F6', clear=False)
#切换到实物
def gazebo_or_real(self):
self.real_flag = self.checkBox_gazebo.isChecked()
if(self.real_flag):
self.sub_force_path = "/ft_sensor_topic"
self.lineEdit_sub_f.setText(self.sub_force_path)
self.sub_pos_path = "/joint_states"
self.lineEdit_sub_qq.setText(self.sub_pos_path)
self.pub_path = "/all_joints_position_group_controller/command"
self.lineEdit_pub_qq.setText(self.pub_path)
else:
self.sub_force_path = "/ft_sensor_topic"
self.lineEdit_sub_f.setText(self.sub_force_path)
self.sub_pos_path = "/armc/joint_states"
self.lineEdit_sub_qq.setText(self.sub_pos_path)
self.pub_path = "/armc/joint_positions_controller/command"
self.lineEdit_pub_qq.setText(self.pub_path)
#读取给定关节角度
def read_wish_pos(self):
qq = np.zeros(7)
qq[0] = self.lineEdit_q1.text()
qq[1] = self.lineEdit_q2.text()
qq[2] = self.lineEdit_q3.text()
qq[3] = self.lineEdit_q4.text()
qq[4] = self.lineEdit_q5.text()
qq[5] = self.lineEdit_q6.text()
qq[6] = self.lineEdit_q7.text()
msg_pos = "规划目标点\n" + \
"q1:" + str(qq[0]) + "\n" + "q2:" + str(qq[1]) +\
"\n" + "q3:" + str(qq[2]) + "\n" + "q4:" + str(qq[3]) +\
"\n" + "q5:" + str(qq[4]) + "\n" + "q6:" + str(qq[5]) + \
"\n" + "q7:" + str(qq[6])
self.textEdit.setText(msg_pos)
self.qq_go = np.copy(qq*np.pi/180.0)
#规划函数
def plan(self):
#获得规划起点
qq_b = np.array(self.state_qq_list[-1])
#调用规划函数
[qq,qv,T] = gf.q_joint_space_plan(qq_b, self.qq_go)
#调用绘图函数
k =len(qq)
t = np.linspace(0, T*(k-1), k)
self.T = T
#绘制关节角位置速度图
self.plot_joint(t, qq, t, np.zeros([k, 6]))
#将规划好的位置定义为全局变量
self.command_qq_list = np.copy(qq)
##关节角订阅回调函数
def joint_callback(self, msg):
qq = np.zeros(self.n)
for i in range(self.n):
qq[i] = msg.position[i]
self.state_t = self.state_t + self.T
self.state_qq_list.append(qq)
self.state_t_list.append(self.state_t)
# 仅记录100个数据点
del self.state_t_list[0]
del self.state_qq_list[0]
##关节角订阅回调函数
def force_callback(self, msg):
f = np.zeros(6)
f[0] = msg.wrench.force.x
f[1] = msg.wrench.force.y
f[2] = msg.wrench.force.z
f[3] = msg.wrench.torque.x
f[4] = msg.wrench.torque.y
f[5] = msg.wrench.torque.z
# 存储数据
self.state_f_list.append(f)
# 仅记录1000个数据点
del self.state_f_list[0]
##末端力订阅线程
def thread_spin(self):
rospy.spin()
def probar_show(self):
self.step_p = self.step_p + 1
self.progressBar.setValue(self.step_p)
if(self.step_p>99):
self.timer_p.stop()
def stop(self):
self.run_flag = False
def realtime_plot(self):
plot_t = np.array(self.state_t_list)
plot_qq = np.array(self.state_qq_list)
plot_f = np.array(self.state_f_list)
self.plot_joint(plot_t, plot_qq, plot_t, plot_f)
def run_topic(self):
#先读取地址
self.sub_force_path = str(self.lineEdit_sub_f.text())
self.sub_pos_path = str(self.lineEdit_sub_qq.text())
self.pub_path = str(self.lineEdit_pub_qq.text())
# 运行话题
rospy.init_node('upper_controller_node')
rospy.Subscriber(self.sub_pos_path, JointState, self.joint_callback)
rospy.Subscriber(self.sub_force_path, WrenchStamped, self.force_callback)
self.pub = rospy.Publisher(self.pub_path, Float64MultiArray, queue_size=100)
# 运行线程1,收话题线程
t1 = threading.Thread(target=self.thread_spin) # 末端位置订阅线程
msg_tip = "upper_controller_node run!"
self.textEdit.setText(msg_tip)
t1.start()
def begin_function(self):
#运行标签启动
self.run_flag = True
#求取数据长度
kk = len(self.command_qq_list)
if(not self.real_flag):
#进度条显示时间间隔
show_time = int(kk*self.T*10)
#设置ProgressBar,用Qtimer开线程处理(线程3)
self.step_p = 0
self.timer_p = QTimer()
self.timer_p.timeout.connect(self.probar_show)
self.timer_p.start(show_time)
#设置绘图,用Qtimer开线程处理(线程4)
self.timer_plot = QTimer()
self.timer_plot.timeout.connect(self.realtime_plot)
self.timer_plot.start(1000)
#发送关节角度
rate = rospy.Rate(100)
k = 0
while not rospy.is_shutdown():
#检测是否启动急停
if(not self.run_flag or k==kk):
if(not self.real_flag):
self.timer_p.stop()
self.timer_plot.stop()
break
#发送数据
command_data = Float64MultiArray()
if (k < kk):
command_data.data = self.command_qq_list[k, 0:self.n]
self.pub.publish(command_data)
if(k%20==0):
pub_msg = "armc" + "第" + str(k) + "次" + "publisher data is: " + '\n'\
"q1:" + str(command_data.data[0]) + '\n' \
"q2:" + str(command_data.data[1]) + '\n' \
"q3:" + str(command_data.data[2]) + '\n'\
"q4:" + str(command_data.data[3]) + '\n' \
"q5:" + str(command_data.data[4]) + '\n' \
"q6:" + str(command_data.data[5]) + '\n' \
"q7:" + str(command_data.data[6]) + '\n'
self.textEdit.setText(pub_msg)
QApplication.processEvents()
k = k + 1
rate.sleep()
# ===============窗口跳转函数================#
def gotoArmc1(self):
self.hide()
self.armc1 = ArmcWindow1()
self.armc1.show()
#***************************armc窗口1:关节空间规划********************************#
class ArmcWindow1(QMainWindow, Ui_ArmcForm1):
# 建立全局变量
state_qq_list = list(np.zeros([1000, 7]))
state_f_list = list(np.zeros([1000, 6]))
state_t_list = list(np.zeros(1000))
state_t = 0
def __init__(self, parent=None):
super(ArmcWindow1, self).__init__(parent)
self.T = 0.01
self.run_flag = True # 开始或停止标签
self.vel_flag = False
self.real_flag = False
self.sub_force_path = "/ft_sensor_topic"
self.sub_pos_path = "/armc/joint_states"
self.pub_path = "/armc/joint_positions_controller/command"
self.n = 7 # 机械臂关节数
self.setupUi(self)
self.initUI()
def initUI(self):
# ======================菜单栏功能模块=======================#
# 创建菜单
menubar = self.menuBar()
mainMenu = menubar.addMenu('&Main')
# 文件菜单:返回主窗口
openMain = QAction(QIcon('exit.png'), 'main window ', self)
openMain.setShortcut('Ctrl+z')
openMain.setStatusTip('Return main window')
openMain.triggered.connect(self.gotoMain)
mainMenu.addAction(openMain)
# =======================绘图相关设置=======================#
self.p1, self.p2 = self.set_graph_ui() # 设置绘图窗口
# =======================按钮功能模块=======================#
self.button_begin.clicked.connect(self.begin_function)
self.button_stop.clicked.connect(self.stop)
self.button_wish_pos.clicked.connect(self.read_wish_pos)
self.button_receive.clicked.connect(self.run_topic)
self.button_plan.clicked.connect(self.plan)
self.checkBox_gazebo.stateChanged.connect(self.vel_or_real)
self.checkBox_vel.stateChanged.connect(self.vel_or_real)
# 打开文件的地址和内容
def fileOpen(self):
# 打开文件操作
fname = QFileDialog.getOpenFileName(self, 'Open file', '/home')
if fname[0]:
f = open(fname[0], 'r')
self.filedir = fname[0]
with f:
data = f.read()
self.pubdata = data
self.textEdit.setText(data)
# ===============按钮功能模块相关函数================#
# 采用pyqtgraph绘制曲线,添加画板
def set_graph_ui(self):
pg.setConfigOptions(antialias=True) # pg全局变量设置函数,antialias=True开启曲线抗锯齿
win1 = pg.GraphicsLayoutWidget() # 创建pg layout,可实现数据界面布局自动管理
win2 = pg.GraphicsLayoutWidget()
# pg绘图窗口可以作为一个widget添加到GUI中的graph_layout,当然也可以添加到Qt其他所有的容器中
self.horizontalLayout_1.addWidget(win1)
self.horizontalLayout_2.addWidget(win2)
p1 = win1.addPlot(title="joint pos") # 添加第一个绘图窗口
p1.setLabel('left', text='pos/rad', color='#ffffff') # y轴设置函数
p1.showGrid(x=True, y=True) # 栅格设置函数
p1.setLogMode(x=False, y=False) # False代表线性坐标轴,True代表对数坐标轴
p1.setLabel('bottom', text='time', units='s') # x轴设置函数
p1.addLegend(size=(50, 30)) # 可选择是否添加legend
p2 = win2.addPlot(title="joint vel") # 添加第一个绘图窗口
p2.setLabel('left', text='vel/(rad/s)', color='#ffffff') # y轴设置函数
p2.showGrid(x=True, y=True) # 栅格设置函数
p2.setLogMode(x=False, y=False) # False代表线性坐标轴,True代表对数坐标轴
p2.setLabel('bottom', text='time', units='s') # x轴设置函数
p2.addLegend(size=(50, 30))
return p1, p2
# 绘画关节角和关节角速度曲线
def plot_pos(self, t1, qq):
# 绘制位置图,表示颜色的单字符串(b,g,r,c,m,y,k,w)
self.p1.plot(t1, qq[:, 0], pen='b', name='qq1', clear=True)
self.p1.plot(t1, qq[:, 1], pen='g', name='qq2', clear=False)
self.p1.plot(t1, qq[:, 2], pen='r', name='qq3', clear=False)
self.p1.plot(t1, qq[:, 3], pen='c', name='qq4', clear=False)
self.p1.plot(t1, qq[:, 4], pen='m', name='qq5', clear=False)
self.p1.plot(t1, qq[:, 5], pen='y', name='qq6', clear=False)
self.p1.plot(t1, qq[:, 6], pen='w', name='qq7', clear=False)
def plot_vel(self, t1, qv):
# 绘制位置图,表示颜色的单字符串(b,g,r,c,m,y,k,w)
self.p2.plot(t1, qv[:, 0], pen='b', name='qv1', clear=True)
self.p2.plot(t1, qv[:, 1], pen='g', name='qv2', clear=False)
self.p2.plot(t1, qv[:, 2], pen='r', name='qv3', clear=False)
self.p2.plot(t1, qv[:, 3], pen='c', name='qv4', clear=False)
self.p2.plot(t1, qv[:, 4], pen='m', name='qv5', clear=False)
self.p2.plot(t1, qv[:, 5], pen='y', name='qv6', clear=False)
self.p2.plot(t1, qv[:, 6], pen='w', name='qv7', clear=False)
# 切换到实物
def vel_or_real(self):
self.real_flag = self.checkBox_gazebo.isChecked()
self.vel_flag = self.checkBox_vel.isChecked()
if (self.real_flag):
if(self.vel_flag):
self.sub_force_path = "/armc/ft_sensor_topic"
self.lineEdit_sub_f.setText(self.sub_force_path)
self.sub_pos_path = "/joint_states"
self.lineEdit_sub_qq.setText(self.sub_pos_path)
self.pub_path = "/all_joints_velocity_group_controller/command"
self.lineEdit_pub_qq.setText(self.pub_path)
else:
self.sub_force_path = "/armc/ft_sensor_topic"
self.lineEdit_sub_f.setText(self.sub_force_path)
self.sub_pos_path = "/joint_states"
self.lineEdit_sub_qq.setText(self.sub_pos_path)
self.pub_path = "/all_joints_position_group_controller/command"
self.lineEdit_pub_qq.setText(self.pub_path)
else:
self.sub_force_path = "/ft_sensor_topic"
self.lineEdit_sub_f.setText(self.sub_force_path)
self.sub_pos_path = "/armc/joint_states"
self.lineEdit_sub_qq.setText(self.sub_pos_path)
self.pub_path = "/armc/joint_positions_controller/command"
self.lineEdit_pub_qq.setText(self.pub_path)
# 读取给定关节角度
def read_wish_pos(self):
qq = np.zeros(7)
qq[0] = self.lineEdit_q1.text()
qq[1] = self.lineEdit_q2.text()
qq[2] = self.lineEdit_q3.text()
qq[3] = self.lineEdit_q4.text()
qq[4] = self.lineEdit_q5.text()
qq[5] = self.lineEdit_q6.text()
qq[6] = self.lineEdit_q7.text()
msg_pos = "规划目标点\n" + \
"q1:" + str(qq[0]) + "\n" + "q2:" + str(qq[1]) + \
"\n" + "q3:" + str(qq[2]) + "\n" + "q4:" + str(qq[3]) + \
"\n" + "q5:" + str(qq[4]) + "\n" + "q6:" + str(qq[5]) + \
"\n" + "q7:" + str(qq[6])
self.textEdit.setText(msg_pos)
self.qq_go = np.copy(qq * np.pi / 180.0)
# 规划函数
def plan(self):
# 获得规划起点
qq_b = np.array(self.state_qq_list[-1])
# 调用规划函数
[qq, qv, T] = gf.q_joint_space_plan(qq_b, self.qq_go)
# 调用绘图函数
k = len(qq)
t = np.linspace(0, T * (k - 1), k)
self.T = T
# 绘制关节角位置图
self.plot_pos(t, qq)
# 绘制关节角速度图
self.plot_vel(t, qv)
# 将规划好的位置定义为全局变量
self.command_qq_list = np.copy(qq)
self.command_qv_list = np.copy(qv)
##关节角订阅回调函数
def joint_callback(self, msg):
qq = np.zeros(self.n)
for i in range(self.n):
qq[i] = msg.position[i]
self.state_t = self.state_t + self.T
self.state_qq_list.append(qq)
self.state_t_list.append(self.state_t)
# 仅记录100个数据点
del self.state_t_list[0]
del self.state_qq_list[0]
##关节角订阅回调函数
def force_callback(self, msg):
f = np.zeros(6)
f[0] = msg.wrench.force.x
f[1] = msg.wrench.force.y
f[2] = msg.wrench.force.z
f[3] = msg.wrench.torque.x
f[4] = msg.wrench.torque.y
f[5] = msg.wrench.torque.z
# 存储数据
self.state_f_list.append(f)
# 仅记录1000个数据点
del self.state_f_list[0]
##末端力订阅线程
def thread_spin(self):
rospy.spin()
def probar_show(self):
self.step_p = self.step_p + 1
self.progressBar.setValue(self.step_p)
if (self.step_p > 99):
self.timer_p.stop()
def stop(self):
self.run_flag = False
def realtime_plot(self):
plot_t = np.array(self.state_t_list)
plot_qq = np.array(self.state_qq_list)
#plot_f = np.array(self.state_f_list)
self.plot_pos(plot_t, plot_qq)
def run_topic(self):
# 先读取地址
self.sub_force_path = str(self.lineEdit_sub_f.text())
self.sub_pos_path = str(self.lineEdit_sub_qq.text())
self.pub_path = str(self.lineEdit_pub_qq.text())
# 运行话题
rospy.init_node('upper_controller_node')
rospy.Subscriber(self.sub_pos_path, JointState, self.joint_callback)
#rospy.Subscriber(self.sub_force_path, WrenchStamped, self.force_callback)
self.pub = rospy.Publisher(self.pub_path, Float64MultiArray, queue_size=100)
# 运行线程1,收话题线程
t1 = threading.Thread(target=self.thread_spin) # 末端位置订阅线程
msg_tip = "upper_controller_node run!"
self.textEdit.setText(msg_tip)
t1.start()
def begin_function(self):
if(self.vel_flag):
self.run_vel()
else:
self.run_pos()
def run_pos(self):
# 运行标签启动
self.run_flag = True
# 求取数据长度
kk = len(self.command_qq_list)
if (not self.real_flag):
# 进度条显示时间间隔
show_time = int(kk * self.T * 10)
# 设置ProgressBar,用Qtimer开线程处理(线程3)
self.step_p = 0
self.timer_p = QTimer()
self.timer_p.timeout.connect(self.probar_show)
self.timer_p.start(show_time)
# 设置绘图,用Qtimer开线程处理(线程4)
self.timer_plot = QTimer()
self.timer_plot.timeout.connect(self.realtime_plot)
self.timer_plot.start(1000)
# 发送关节角度
rate = rospy.Rate(100)
k = 0
while not rospy.is_shutdown():
# 检测是否启动急停
if (not self.run_flag):
if (not self.real_flag):
self.timer_p.stop()
self.timer_plot.stop()
break
# 发送数据
command_data = Float64MultiArray()
if (k < kk):
command_data.data = self.command_qq_list[k, 0:self.n]
else:
break
command_data.data = self.command_qq_list[-1, 0:self.n]
self.pub.publish(command_data)
if (k/10 == 0):
pub_msg = "armc" + "第" + str(k) + "次" + "publisher data is: " + '\n' \
"q1:" + str(
command_data.data[0]) + '\n' \
"q2:" + str(command_data.data[1]) + '\n' \
"q3:" + str(
command_data.data[2]) + '\n' \
"q4:" + str(command_data.data[3]) + '\n' \
"q5:" + str(
command_data.data[4]) + '\n' \
"q6:" + str(command_data.data[5]) + '\n' \
"q7:" + str(
command_data.data[6]) + '\n'
self.textEdit.setText(pub_msg)
QApplication.processEvents()
k = k + 1
rate.sleep()
def run_vel(self):
# 运行标签启动
self.run_flag = True
# 求取数据长度
kk = len(self.command_qv_list)
if (not self.real_flag):
# 进度条显示时间间隔
show_time = int(kk * self.T * 10)
# 设置ProgressBar,用Qtimer开线程处理(线程3)
self.step_p = 0
self.timer_p = QTimer()
self.timer_p.timeout.connect(self.probar_show)
self.timer_p.start(show_time)
# 设置绘图,用Qtimer开线程处理(线程4)
self.timer_plot = QTimer()
self.timer_plot.timeout.connect(self.realtime_plot)
self.timer_plot.start(1000)
# 发送关节角度
rate = rospy.Rate(100)
k = 0
while not rospy.is_shutdown():
# 检测是否启动急停
if (not self.run_flag):
if (not self.real_flag):
self.timer_p.stop()
self.timer_plot.stop()
break
# 发送数据
command_data = Float64MultiArray()
if (k < kk):
command_data.data = self.command_qv_list[k, 0:self.n]
else:
break
command_data.data = np.zeros(self.n)
self.pub.publish(command_data)
if (k%50 == 0):
pub_msg = "armc" + "第" + str(k) + "次" + "publisher data is: " + '\n' \
"qv1:" + str(
command_data.data[0]) + '\n' \
"qv2:" + str(command_data.data[1]) + '\n' \
"qv3:" + str(
command_data.data[2]) + '\n' \
"qv4:" + str(command_data.data[3]) + '\n' \
"qv5:" + str(
command_data.data[4]) + '\n' \
"qv6:" + str(command_data.data[5]) + '\n' \
"qv7:" + str(
command_data.data[6]) + '\n'
self.textEdit.setText(pub_msg)
QApplication.processEvents()
k = k + 1
rate.sleep()
# ===============窗口跳转函数================#
def gotoMain(self):
self.hide()
self.main_windon = MainWindow()
self.main_windon.show()
if __name__ == '__main__':
app = QApplication(sys.argv)
myWin = MainWindow()
myWin.show()
sys.exit(app.exec_())
界面需要调用的相关函数,实现算法:gui_function_demo.py
#!/usr/bin/env python
#-*-coding:utf-8-*-
#本文档用于界面相关函数
#程序员:陈永*
#版权:哈尔滨工业大学
#日期:初稿:2020.12.21
#系统函数
import numpy as np
from math import pi
# 5次多项式插值求取求取一段时间的离散数值点,多变量
def interp5rdPoly(q0, qv0, qa0, qf, qvf, qaf, tf, dt):
'''
本函数用5项插值将离散数据连续化,多变量
input:q0,qv0,qa0起点位置速度加速度
qf,qvf,qaf终点位置速度加速度
tf终点时间,dt时间间隔
output:[q,qv,qa] 对应时刻位置速度加速度
'''
n = len(q0)
k = np.floor(tf / dt).astype(int) + 1
# 求取5次多项式插值系数
a0 = np.zeros(n)
a1 = np.zeros(n)
a2 = np.zeros(n)
a3 = np.zeros(n)
a4 = np.zeros(n)
a5 = np.zeros(n)
for i in range(n):
a0[i] = q0[i]
a1[i] = qv0[i]
a2[i] = qa0[i] / 2.0
a3[i] = (20 * (qf[i] - q0[i]) - (8 * qvf[i] + 12 * qv0[i]) * tf + (qaf[i] - 3 * qa0[i]) * tf * tf) / (
2 * pow(tf, 3))
a4[i] = (-30 * (qf[i] - q0[i]) + (14 * qvf[i] + 16 * qv0[i]) * tf - (2 * qaf[i] - 3 * qa0[i]) * tf * tf) / (
2 * pow(tf, 4))
a5[i] = (12 * (qf[i] - q0[i]) - (60 * qvf[i] + 6 * qv0[i]) * tf + (qaf[i] - qa0[i]) * tf * tf) / (
2 * pow(tf, 5))
# 数据点求取
qq = np.zeros([k, n])
qv = np.zeros([k, n])
qa = np.zeros([k, n])
t_seq = np.linspace(0, tf, k)
for i in range(k):
t = t_seq[i]
for j in range(n):
qq[i, j] = a0[j] + a1[j] * t + a2[j] * pow(t, 2) + a3[j] * pow(t, 3) + a4[j] * pow(t, 4) + a5[j] * pow(t, 5)
qv[i, j] = a1[j] + 2 * a2[j] * t + 3 * a3[j] * pow(t, 2) + 4 * a4[j] * pow(t, 3) + 5 * a5[j] * pow(t, 4)
qa[i, j] = 2 * a2[j] + 6 * a3[j] * t + 12 * a4[j] * pow(t, 2) + 20 * a5[j] * pow(t, 3)
return [qq, qv, qa]
#=====================从一个起点到另一个点=====================#
def pos1_to_pos2(qq1,qq2,T,tf):
n = len(qq1)
q0 = np.zeros(n)
[qq, qv, qa] = interp5rdPoly(qq1, q0, q0, qq2, q0, q0, tf, T)
return [qq, qv, qa]
# ===============================规划模块================================#
#主界面中,用于规划关节空间点到点的运动
def q_joint_space_plan(qq_b, qq_e, T=0.01):
'''
:param qq_b: 规划起始点
:param qq_e: 规划终止点
:return:
'''
#给定运动速度5rmp/min
vel = 5*2*pi/60.0
#关节角度转换到弧度单位rad
qqb = qq_b
qqe = qq_e
#计算总时长
q_max = np.max(np.abs(qqe - qqb))
t = q_max/vel
if(t < 10):
t = 10
[qq,qv,qa] = pos1_to_pos2(qqb, qqe, T, t)
return [qq, qv, T]
#关节空间规划,给定时间
def q_joint_space_plan_time(qq_b, qq_e, T=0.01,t=10):
'''
:param qq_b:
:param qq_e:
:param T:
:param t:
:return:
'''
[qq, qv, qa] = pos1_to_pos2(qq_b, qq_e, T, t)
return [qq, qv, qa]
#采用绘图UI生成的主界面函数:main_windon.py
# -*- coding: utf-8 -*-
# Form implementation generated from reading ui file 'main_windon.ui'
#
# Created by: PyQt5 UI code generator 5.5.1
#
# WARNING! All changes made in this file will be lost!
from PyQt5 import QtCore, QtGui, QtWidgets
class Ui_MainWindow(object):
def setupUi(self, MainWindow):
MainWindow.setObjectName("MainWindow")
MainWindow.resize(1238, 903)
MainWindow.setIconSize(QtCore.QSize(16, 16))
MainWindow.setAnimated(False)
self.centralwidget = QtWidgets.QWidget(MainWindow)
self.centralwidget.setObjectName("centralwidget")
self.horizontalLayoutWidget = QtWidgets.QWidget(self.centralwidget)
self.horizontalLayoutWidget.setGeometry(QtCore.QRect(10, 10, 451, 401))
self.horizontalLayoutWidget.setObjectName("horizontalLayoutWidget")
self.horizontalLayout_1 = QtWidgets.QHBoxLayout(self.horizontalLayoutWidget)
self.horizontalLayout_1.setObjectName("horizontalLayout_1")
self.horizontalLayoutWidget_2 = QtWidgets.QWidget(self.centralwidget)
self.horizontalLayoutWidget_2.setGeometry(QtCore.QRect(10, 410, 451, 431))
self.horizontalLayoutWidget_2.setObjectName("horizontalLayoutWidget_2")
self.horizontalLayout_2 = QtWidgets.QHBoxLayout(self.horizontalLayoutWidget_2)
self.horizontalLayout_2.setObjectName("horizontalLayout_2")
self.horizontalLayoutWidget_5 = QtWidgets.QWidget(self.centralwidget)
self.horizontalLayoutWidget_5.setGeometry(QtCore.QRect(460, 410, 511, 431))
self.horizontalLayoutWidget_5.setObjectName("horizontalLayoutWidget_5")
self.horizontalLayout_5 = QtWidgets.QHBoxLayout(self.horizontalLayoutWidget_5)
self.horizontalLayout_5.setObjectName("horizontalLayout_5")
self.frame = QtWidgets.QFrame(self.horizontalLayoutWidget_5)
self.frame.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame.setObjectName("frame")
self.textEdit = QtWidgets.QTextEdit(self.frame)
self.textEdit.setGeometry(QtCore.QRect(10, 30, 461, 301))
self.textEdit.setObjectName("textEdit")
self.label = QtWidgets.QLabel(self.frame)
self.label.setGeometry(QtCore.QRect(160, 0, 131, 31))
self.label.setObjectName("label")
self.progressBar = QtWidgets.QProgressBar(self.frame)
self.progressBar.setGeometry(QtCore.QRect(70, 360, 401, 31))
self.progressBar.setProperty("value", 24)
self.progressBar.setObjectName("progressBar")
self.label_2 = QtWidgets.QLabel(self.frame)
self.label_2.setGeometry(QtCore.QRect(20, 360, 51, 31))
self.label_2.setObjectName("label_2")
self.horizontalLayout_5.addWidget(self.frame)
self.horizontalLayoutWidget_6 = QtWidgets.QWidget(self.centralwidget)
self.horizontalLayoutWidget_6.setGeometry(QtCore.QRect(460, 10, 511, 401))
self.horizontalLayoutWidget_6.setObjectName("horizontalLayoutWidget_6")
self.horizontalLayout_6 = QtWidgets.QHBoxLayout(self.horizontalLayoutWidget_6)
self.horizontalLayout_6.setObjectName("horizontalLayout_6")
self.frame_4 = QtWidgets.QFrame(self.horizontalLayoutWidget_6)
self.frame_4.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame_4.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame_4.setObjectName("frame_4")
self.verticalLayoutWidget_3 = QtWidgets.QWidget(self.frame_4)
self.verticalLayoutWidget_3.setGeometry(QtCore.QRect(0, 0, 491, 241))
self.verticalLayoutWidget_3.setObjectName("verticalLayoutWidget_3")
self.verticalLayout_3 = QtWidgets.QVBoxLayout(self.verticalLayoutWidget_3)
self.verticalLayout_3.setObjectName("verticalLayout_3")
self.frame_2 = QtWidgets.QFrame(self.verticalLayoutWidget_3)
self.frame_2.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame_2.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame_2.setObjectName("frame_2")
self.label_11 = QtWidgets.QLabel(self.frame_2)
self.label_11.setGeometry(QtCore.QRect(170, 10, 161, 31))
self.label_11.setObjectName("label_11")
self.label_30 = QtWidgets.QLabel(self.frame_2)
self.label_30.setGeometry(QtCore.QRect(10, 160, 71, 33))
self.label_30.setObjectName("label_30")
self.lineEdit_sub_f = QtWidgets.QLineEdit(self.frame_2)
self.lineEdit_sub_f.setGeometry(QtCore.QRect(80, 40, 381, 41))
self.lineEdit_sub_f.setObjectName("lineEdit_sub_f")
self.label_12 = QtWidgets.QLabel(self.frame_2)
self.label_12.setGeometry(QtCore.QRect(10, 40, 61, 33))
self.label_12.setObjectName("label_12")
self.label_13 = QtWidgets.QLabel(self.frame_2)
self.label_13.setGeometry(QtCore.QRect(10, 100, 71, 33))
self.label_13.setObjectName("label_13")
self.lineEdit_sub_qq = QtWidgets.QLineEdit(self.frame_2)
self.lineEdit_sub_qq.setGeometry(QtCore.QRect(80, 100, 381, 41))
self.lineEdit_sub_qq.setObjectName("lineEdit_sub_qq")
self.lineEdit_pub_qq = QtWidgets.QLineEdit(self.frame_2)
self.lineEdit_pub_qq.setGeometry(QtCore.QRect(80, 160, 381, 41))
self.lineEdit_pub_qq.setObjectName("lineEdit_pub_qq")
self.verticalLayout_3.addWidget(self.frame_2)
self.button_receive = QtWidgets.QPushButton(self.frame_4)
self.button_receive.setGeometry(QtCore.QRect(130, 290, 221, 61))
self.button_receive.setIconSize(QtCore.QSize(16, 16))
self.button_receive.setAutoRepeat(False)
self.button_receive.setAutoExclusive(False)
self.button_receive.setAutoRepeatDelay(400)
self.button_receive.setAutoRepeatInterval(200)
self.button_receive.setAutoDefault(True)
self.button_receive.setFlat(False)
self.button_receive.setObjectName("button_receive")
self.horizontalLayout_6.addWidget(self.frame_4)
self.verticalLayoutWidget = QtWidgets.QWidget(self.centralwidget)
self.verticalLayoutWidget.setGeometry(QtCore.QRect(970, 410, 261, 431))
self.verticalLayoutWidget.setObjectName("verticalLayoutWidget")
self.verticalLayout = QtWidgets.QVBoxLayout(self.verticalLayoutWidget)
self.verticalLayout.setObjectName("verticalLayout")
self.frame_6 = QtWidgets.QFrame(self.verticalLayoutWidget)
self.frame_6.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame_6.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame_6.setObjectName("frame_6")
self.label_4 = QtWidgets.QLabel(self.frame_6)
self.label_4.setGeometry(QtCore.QRect(10, 160, 31, 33))
self.label_4.setObjectName("label_4")
self.lineEdit_q5 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q5.setGeometry(QtCore.QRect(50, 210, 181, 33))
self.lineEdit_q5.setObjectName("lineEdit_q5")
self.label_5 = QtWidgets.QLabel(self.frame_6)
self.label_5.setGeometry(QtCore.QRect(10, 260, 31, 33))
self.label_5.setObjectName("label_5")
self.lineEdit_q6 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q6.setGeometry(QtCore.QRect(50, 260, 181, 33))
self.lineEdit_q6.setObjectName("lineEdit_q6")
self.label_6 = QtWidgets.QLabel(self.frame_6)
self.label_6.setGeometry(QtCore.QRect(10, 300, 31, 33))
self.label_6.setObjectName("label_6")
self.lineEdit_q7 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q7.setGeometry(QtCore.QRect(50, 300, 181, 33))
self.lineEdit_q7.setObjectName("lineEdit_q7")
self.lineEdit_q4 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q4.setGeometry(QtCore.QRect(50, 160, 180, 33))
self.lineEdit_q4.setObjectName("lineEdit_q4")
self.label_7 = QtWidgets.QLabel(self.frame_6)
self.label_7.setGeometry(QtCore.QRect(10, 210, 31, 33))
self.label_7.setObjectName("label_7")
self.label_3 = QtWidgets.QLabel(self.frame_6)
self.label_3.setGeometry(QtCore.QRect(60, 0, 151, 31))
self.label_3.setObjectName("label_3")
self.label_8 = QtWidgets.QLabel(self.frame_6)
self.label_8.setGeometry(QtCore.QRect(10, 120, 31, 33))
self.label_8.setObjectName("label_8")
self.lineEdit_q3 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q3.setGeometry(QtCore.QRect(50, 120, 180, 33))
self.lineEdit_q3.setObjectName("lineEdit_q3")
self.label_9 = QtWidgets.QLabel(self.frame_6)
self.label_9.setGeometry(QtCore.QRect(10, 80, 31, 33))
self.label_9.setObjectName("label_9")
self.lineEdit_q2 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q2.setGeometry(QtCore.QRect(50, 80, 180, 33))
self.lineEdit_q2.setObjectName("lineEdit_q2")
self.label_10 = QtWidgets.QLabel(self.frame_6)
self.label_10.setGeometry(QtCore.QRect(10, 40, 31, 33))
self.label_10.setObjectName("label_10")
self.lineEdit_q1 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q1.setGeometry(QtCore.QRect(50, 40, 180, 33))
self.lineEdit_q1.setObjectName("lineEdit_q1")
self.button_wish_pos = QtWidgets.QPushButton(self.frame_6)
self.button_wish_pos.setGeometry(QtCore.QRect(90, 360, 91, 41))
self.button_wish_pos.setAutoDefault(True)
self.button_wish_pos.setObjectName("button_wish_pos")
self.lineEdit_q4.raise_()
self.label_4.raise_()
self.lineEdit_q5.raise_()
self.label_7.raise_()
self.label_5.raise_()
self.lineEdit_q6.raise_()
self.label_6.raise_()
self.lineEdit_q7.raise_()
self.label_3.raise_()
self.label_8.raise_()
self.lineEdit_q3.raise_()
self.label_9.raise_()
self.lineEdit_q2.raise_()
self.label_10.raise_()
self.lineEdit_q1.raise_()
self.button_wish_pos.raise_()
self.verticalLayout.addWidget(self.frame_6)
self.verticalLayoutWidget_2 = QtWidgets.QWidget(self.centralwidget)
self.verticalLayoutWidget_2.setGeometry(QtCore.QRect(970, 10, 261, 401))
self.verticalLayoutWidget_2.setObjectName("verticalLayoutWidget_2")
self.verticalLayout_2 = QtWidgets.QVBoxLayout(self.verticalLayoutWidget_2)
self.verticalLayout_2.setObjectName("verticalLayout_2")
self.frame_5 = QtWidgets.QFrame(self.verticalLayoutWidget_2)
self.frame_5.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame_5.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame_5.setObjectName("frame_5")
self.button_begin = QtWidgets.QPushButton(self.frame_5)
self.button_begin.setGeometry(QtCore.QRect(10, 20, 221, 61))
self.button_begin.setIconSize(QtCore.QSize(16, 16))
self.button_begin.setAutoRepeat(False)
self.button_begin.setAutoExclusive(False)
self.button_begin.setAutoRepeatDelay(400)
self.button_begin.setAutoRepeatInterval(200)
self.button_begin.setAutoDefault(True)
self.button_begin.setFlat(False)
self.button_begin.setObjectName("button_begin")
self.button_stop = QtWidgets.QPushButton(self.frame_5)
self.button_stop.setGeometry(QtCore.QRect(10, 110, 221, 61))
self.button_stop.setAutoDefault(True)
self.button_stop.setObjectName("button_stop")
self.layoutWidget_2 = QtWidgets.QWidget(self.frame_5)
self.layoutWidget_2.setGeometry(QtCore.QRect(20, 200, 201, 91))
self.layoutWidget_2.setObjectName("layoutWidget_2")
self.verticalLayout_4 = QtWidgets.QVBoxLayout(self.layoutWidget_2)
self.verticalLayout_4.setObjectName("verticalLayout_4")
self.checkBox_UR5 = QtWidgets.QCheckBox(self.layoutWidget_2)
self.checkBox_UR5.setObjectName("checkBox_UR5")
self.verticalLayout_4.addWidget(self.checkBox_UR5)
self.checkBox_gazebo = QtWidgets.QCheckBox(self.layoutWidget_2)
self.checkBox_gazebo.setObjectName("checkBox_gazebo")
self.verticalLayout_4.addWidget(self.checkBox_gazebo)
self.button_plan = QtWidgets.QPushButton(self.frame_5)
self.button_plan.setGeometry(QtCore.QRect(10, 300, 221, 61))
self.button_plan.setAutoDefault(True)
self.button_plan.setObjectName("button_plan")
self.verticalLayout_2.addWidget(self.frame_5)
MainWindow.setCentralWidget(self.centralwidget)
self.menubar = QtWidgets.QMenuBar(MainWindow)
self.menubar.setGeometry(QtCore.QRect(0, 0, 1238, 35))
self.menubar.setDefaultUp(False)
self.menubar.setObjectName("menubar")
MainWindow.setMenuBar(self.menubar)
self.statusbar = QtWidgets.QStatusBar(MainWindow)
self.statusbar.setObjectName("statusbar")
MainWindow.setStatusBar(self.statusbar)
self.retranslateUi(MainWindow)
QtCore.QMetaObject.connectSlotsByName(MainWindow)
def retranslateUi(self, MainWindow):
_translate = QtCore.QCoreApplication.translate
MainWindow.setWindowTitle(_translate("MainWindow", "MainWindow"))
self.label.setText(_translate("MainWindow", "运行内容显示框"))
self.label_2.setText(_translate("MainWindow", "进度:"))
self.label_11.setText(_translate("MainWindow", "读取数据和话题地址"))
self.label_30.setText(_translate("MainWindow", "Pub_qq:"))
self.lineEdit_sub_f.setText(_translate("MainWindow", "/ft_sensor_topic"))
self.label_12.setText(_translate("MainWindow", "Sub_F:"))
self.label_13.setText(_translate("MainWindow", "Sub_qq:"))
self.lineEdit_sub_qq.setText(_translate("MainWindow", "/armc/joint_states"))
self.lineEdit_pub_qq.setText(_translate("MainWindow", "/armc/joint_positions_controller/command"))
self.button_receive.setText(_translate("MainWindow", "接收机器人状态"))
self.label_4.setText(_translate("MainWindow", "q4:"))
self.lineEdit_q5.setText(_translate("MainWindow", "0"))
self.label_5.setText(_translate("MainWindow", "q6:"))
self.lineEdit_q6.setText(_translate("MainWindow", "0"))
self.label_6.setText(_translate("MainWindow", "q7:"))
self.lineEdit_q7.setText(_translate("MainWindow", "0"))
self.lineEdit_q4.setText(_translate("MainWindow", "0"))
self.label_7.setText(_translate("MainWindow", "q5:"))
self.label_3.setText(_translate("MainWindow", "给定关节角q/°"))
self.label_8.setText(_translate("MainWindow", "q3:"))
self.lineEdit_q3.setText(_translate("MainWindow", "0"))
self.label_9.setText(_translate("MainWindow", "q2:"))
self.lineEdit_q2.setText(_translate("MainWindow", "0"))
self.label_10.setText(_translate("MainWindow", "q1:"))
self.lineEdit_q1.setText(_translate("MainWindow", "0"))
self.button_wish_pos.setText(_translate("MainWindow", "目标点"))
self.button_begin.setText(_translate("MainWindow", "开始"))
self.button_stop.setText(_translate("MainWindow", "停止"))
self.checkBox_UR5.setText(_translate("MainWindow", "UR5勾 armc默认"))
self.checkBox_gazebo.setText(_translate("MainWindow", "实物勾 仿真默认"))
self.button_plan.setText(_translate("MainWindow", "规划"))
UI生成的子界面函数:armc_form1.py
# -*- coding: utf-8 -*-
# Form implementation generated from reading ui file 'armc_form1.ui'
#
# Created by: PyQt5 UI code generator 5.5.1
#
# WARNING! All changes made in this file will be lost!
from PyQt5 import QtCore, QtGui, QtWidgets
class Ui_ArmcForm1(object):
def setupUi(self, ArmcForm1):
ArmcForm1.setObjectName("ArmcForm1")
ArmcForm1.resize(1238, 903)
ArmcForm1.setIconSize(QtCore.QSize(16, 16))
ArmcForm1.setAnimated(False)
self.centralwidget = QtWidgets.QWidget(ArmcForm1)
self.centralwidget.setObjectName("centralwidget")
self.horizontalLayoutWidget = QtWidgets.QWidget(self.centralwidget)
self.horizontalLayoutWidget.setGeometry(QtCore.QRect(10, 10, 451, 401))
self.horizontalLayoutWidget.setObjectName("horizontalLayoutWidget")
self.horizontalLayout_1 = QtWidgets.QHBoxLayout(self.horizontalLayoutWidget)
self.horizontalLayout_1.setObjectName("horizontalLayout_1")
self.horizontalLayoutWidget_2 = QtWidgets.QWidget(self.centralwidget)
self.horizontalLayoutWidget_2.setGeometry(QtCore.QRect(10, 410, 451, 431))
self.horizontalLayoutWidget_2.setObjectName("horizontalLayoutWidget_2")
self.horizontalLayout_2 = QtWidgets.QHBoxLayout(self.horizontalLayoutWidget_2)
self.horizontalLayout_2.setObjectName("horizontalLayout_2")
self.horizontalLayoutWidget_5 = QtWidgets.QWidget(self.centralwidget)
self.horizontalLayoutWidget_5.setGeometry(QtCore.QRect(460, 410, 511, 431))
self.horizontalLayoutWidget_5.setObjectName("horizontalLayoutWidget_5")
self.horizontalLayout_5 = QtWidgets.QHBoxLayout(self.horizontalLayoutWidget_5)
self.horizontalLayout_5.setObjectName("horizontalLayout_5")
self.frame = QtWidgets.QFrame(self.horizontalLayoutWidget_5)
self.frame.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame.setObjectName("frame")
self.textEdit = QtWidgets.QTextEdit(self.frame)
self.textEdit.setGeometry(QtCore.QRect(10, 30, 461, 301))
self.textEdit.setObjectName("textEdit")
self.label = QtWidgets.QLabel(self.frame)
self.label.setGeometry(QtCore.QRect(160, 0, 131, 31))
self.label.setObjectName("label")
self.progressBar = QtWidgets.QProgressBar(self.frame)
self.progressBar.setGeometry(QtCore.QRect(70, 360, 401, 31))
self.progressBar.setProperty("value", 24)
self.progressBar.setObjectName("progressBar")
self.label_2 = QtWidgets.QLabel(self.frame)
self.label_2.setGeometry(QtCore.QRect(20, 360, 51, 31))
self.label_2.setObjectName("label_2")
self.horizontalLayout_5.addWidget(self.frame)
self.horizontalLayoutWidget_6 = QtWidgets.QWidget(self.centralwidget)
self.horizontalLayoutWidget_6.setGeometry(QtCore.QRect(460, 10, 511, 401))
self.horizontalLayoutWidget_6.setObjectName("horizontalLayoutWidget_6")
self.horizontalLayout_6 = QtWidgets.QHBoxLayout(self.horizontalLayoutWidget_6)
self.horizontalLayout_6.setObjectName("horizontalLayout_6")
self.frame_4 = QtWidgets.QFrame(self.horizontalLayoutWidget_6)
self.frame_4.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame_4.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame_4.setObjectName("frame_4")
self.verticalLayoutWidget_3 = QtWidgets.QWidget(self.frame_4)
self.verticalLayoutWidget_3.setGeometry(QtCore.QRect(0, 0, 491, 241))
self.verticalLayoutWidget_3.setObjectName("verticalLayoutWidget_3")
self.verticalLayout_3 = QtWidgets.QVBoxLayout(self.verticalLayoutWidget_3)
self.verticalLayout_3.setObjectName("verticalLayout_3")
self.frame_2 = QtWidgets.QFrame(self.verticalLayoutWidget_3)
self.frame_2.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame_2.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame_2.setObjectName("frame_2")
self.label_11 = QtWidgets.QLabel(self.frame_2)
self.label_11.setGeometry(QtCore.QRect(170, 10, 161, 31))
self.label_11.setObjectName("label_11")
self.label_30 = QtWidgets.QLabel(self.frame_2)
self.label_30.setGeometry(QtCore.QRect(10, 160, 71, 33))
self.label_30.setObjectName("label_30")
self.lineEdit_sub_f = QtWidgets.QLineEdit(self.frame_2)
self.lineEdit_sub_f.setGeometry(QtCore.QRect(80, 40, 381, 41))
self.lineEdit_sub_f.setObjectName("lineEdit_sub_f")
self.label_12 = QtWidgets.QLabel(self.frame_2)
self.label_12.setGeometry(QtCore.QRect(10, 40, 61, 33))
self.label_12.setObjectName("label_12")
self.label_13 = QtWidgets.QLabel(self.frame_2)
self.label_13.setGeometry(QtCore.QRect(10, 100, 71, 33))
self.label_13.setObjectName("label_13")
self.lineEdit_sub_qq = QtWidgets.QLineEdit(self.frame_2)
self.lineEdit_sub_qq.setGeometry(QtCore.QRect(80, 100, 381, 41))
self.lineEdit_sub_qq.setObjectName("lineEdit_sub_qq")
self.lineEdit_pub_qq = QtWidgets.QLineEdit(self.frame_2)
self.lineEdit_pub_qq.setGeometry(QtCore.QRect(80, 160, 381, 41))
self.lineEdit_pub_qq.setObjectName("lineEdit_pub_qq")
self.verticalLayout_3.addWidget(self.frame_2)
self.button_receive = QtWidgets.QPushButton(self.frame_4)
self.button_receive.setGeometry(QtCore.QRect(130, 290, 221, 61))
self.button_receive.setIconSize(QtCore.QSize(16, 16))
self.button_receive.setAutoRepeat(False)
self.button_receive.setAutoExclusive(False)
self.button_receive.setAutoRepeatDelay(400)
self.button_receive.setAutoRepeatInterval(200)
self.button_receive.setAutoDefault(True)
self.button_receive.setFlat(False)
self.button_receive.setObjectName("button_receive")
self.horizontalLayout_6.addWidget(self.frame_4)
self.verticalLayoutWidget = QtWidgets.QWidget(self.centralwidget)
self.verticalLayoutWidget.setGeometry(QtCore.QRect(970, 410, 261, 431))
self.verticalLayoutWidget.setObjectName("verticalLayoutWidget")
self.verticalLayout = QtWidgets.QVBoxLayout(self.verticalLayoutWidget)
self.verticalLayout.setObjectName("verticalLayout")
self.frame_6 = QtWidgets.QFrame(self.verticalLayoutWidget)
self.frame_6.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame_6.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame_6.setObjectName("frame_6")
self.label_4 = QtWidgets.QLabel(self.frame_6)
self.label_4.setGeometry(QtCore.QRect(10, 160, 31, 33))
self.label_4.setObjectName("label_4")
self.lineEdit_q5 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q5.setGeometry(QtCore.QRect(50, 210, 181, 33))
self.lineEdit_q5.setObjectName("lineEdit_q5")
self.label_5 = QtWidgets.QLabel(self.frame_6)
self.label_5.setGeometry(QtCore.QRect(10, 260, 31, 33))
self.label_5.setObjectName("label_5")
self.lineEdit_q6 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q6.setGeometry(QtCore.QRect(50, 260, 181, 33))
self.lineEdit_q6.setObjectName("lineEdit_q6")
self.label_6 = QtWidgets.QLabel(self.frame_6)
self.label_6.setGeometry(QtCore.QRect(10, 300, 31, 33))
self.label_6.setObjectName("label_6")
self.lineEdit_q7 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q7.setGeometry(QtCore.QRect(50, 300, 181, 33))
self.lineEdit_q7.setObjectName("lineEdit_q7")
self.lineEdit_q4 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q4.setGeometry(QtCore.QRect(50, 160, 180, 33))
self.lineEdit_q4.setObjectName("lineEdit_q4")
self.label_7 = QtWidgets.QLabel(self.frame_6)
self.label_7.setGeometry(QtCore.QRect(10, 210, 31, 33))
self.label_7.setObjectName("label_7")
self.label_3 = QtWidgets.QLabel(self.frame_6)
self.label_3.setGeometry(QtCore.QRect(60, 0, 151, 31))
self.label_3.setObjectName("label_3")
self.label_8 = QtWidgets.QLabel(self.frame_6)
self.label_8.setGeometry(QtCore.QRect(10, 120, 31, 33))
self.label_8.setObjectName("label_8")
self.lineEdit_q3 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q3.setGeometry(QtCore.QRect(50, 120, 180, 33))
self.lineEdit_q3.setObjectName("lineEdit_q3")
self.label_9 = QtWidgets.QLabel(self.frame_6)
self.label_9.setGeometry(QtCore.QRect(10, 80, 31, 33))
self.label_9.setObjectName("label_9")
self.lineEdit_q2 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q2.setGeometry(QtCore.QRect(50, 80, 180, 33))
self.lineEdit_q2.setObjectName("lineEdit_q2")
self.label_10 = QtWidgets.QLabel(self.frame_6)
self.label_10.setGeometry(QtCore.QRect(10, 40, 31, 33))
self.label_10.setObjectName("label_10")
self.lineEdit_q1 = QtWidgets.QLineEdit(self.frame_6)
self.lineEdit_q1.setGeometry(QtCore.QRect(50, 40, 180, 33))
self.lineEdit_q1.setObjectName("lineEdit_q1")
self.button_wish_pos = QtWidgets.QPushButton(self.frame_6)
self.button_wish_pos.setGeometry(QtCore.QRect(90, 360, 91, 41))
self.button_wish_pos.setAutoDefault(True)
self.button_wish_pos.setObjectName("button_wish_pos")
self.lineEdit_q4.raise_()
self.label_4.raise_()
self.lineEdit_q5.raise_()
self.label_7.raise_()
self.label_5.raise_()
self.lineEdit_q6.raise_()
self.label_6.raise_()
self.lineEdit_q7.raise_()
self.label_3.raise_()
self.label_8.raise_()
self.lineEdit_q3.raise_()
self.label_9.raise_()
self.lineEdit_q2.raise_()
self.label_10.raise_()
self.lineEdit_q1.raise_()
self.button_wish_pos.raise_()
self.verticalLayout.addWidget(self.frame_6)
self.verticalLayoutWidget_2 = QtWidgets.QWidget(self.centralwidget)
self.verticalLayoutWidget_2.setGeometry(QtCore.QRect(970, 10, 261, 401))
self.verticalLayoutWidget_2.setObjectName("verticalLayoutWidget_2")
self.verticalLayout_2 = QtWidgets.QVBoxLayout(self.verticalLayoutWidget_2)
self.verticalLayout_2.setObjectName("verticalLayout_2")
self.frame_5 = QtWidgets.QFrame(self.verticalLayoutWidget_2)
self.frame_5.setFrameShape(QtWidgets.QFrame.StyledPanel)
self.frame_5.setFrameShadow(QtWidgets.QFrame.Raised)
self.frame_5.setObjectName("frame_5")
self.button_begin = QtWidgets.QPushButton(self.frame_5)
self.button_begin.setGeometry(QtCore.QRect(10, 20, 221, 61))
self.button_begin.setIconSize(QtCore.QSize(16, 16))
self.button_begin.setAutoRepeat(False)
self.button_begin.setAutoExclusive(False)
self.button_begin.setAutoRepeatDelay(400)
self.button_begin.setAutoRepeatInterval(200)
self.button_begin.setAutoDefault(True)
self.button_begin.setFlat(False)
self.button_begin.setObjectName("button_begin")
self.button_stop = QtWidgets.QPushButton(self.frame_5)
self.button_stop.setGeometry(QtCore.QRect(10, 110, 221, 61))
self.button_stop.setAutoDefault(True)
self.button_stop.setObjectName("button_stop")
self.layoutWidget_2 = QtWidgets.QWidget(self.frame_5)
self.layoutWidget_2.setGeometry(QtCore.QRect(20, 200, 201, 91))
self.layoutWidget_2.setObjectName("layoutWidget_2")
self.verticalLayout_4 = QtWidgets.QVBoxLayout(self.layoutWidget_2)
self.verticalLayout_4.setObjectName("verticalLayout_4")
self.checkBox_vel = QtWidgets.QCheckBox(self.layoutWidget_2)
self.checkBox_vel.setObjectName("checkBox_vel")
self.verticalLayout_4.addWidget(self.checkBox_vel)
self.checkBox_gazebo = QtWidgets.QCheckBox(self.layoutWidget_2)
self.checkBox_gazebo.setObjectName("checkBox_gazebo")
self.verticalLayout_4.addWidget(self.checkBox_gazebo)
self.button_plan = QtWidgets.QPushButton(self.frame_5)
self.button_plan.setGeometry(QtCore.QRect(10, 300, 221, 61))
self.button_plan.setAutoDefault(True)
self.button_plan.setObjectName("button_plan")
self.verticalLayout_2.addWidget(self.frame_5)
ArmcForm1.setCentralWidget(self.centralwidget)
self.menubar = QtWidgets.QMenuBar(ArmcForm1)
self.menubar.setGeometry(QtCore.QRect(0, 0, 1238, 31))
self.menubar.setDefaultUp(False)
self.menubar.setObjectName("menubar")
ArmcForm1.setMenuBar(self.menubar)
self.statusbar = QtWidgets.QStatusBar(ArmcForm1)
self.statusbar.setObjectName("statusbar")
ArmcForm1.setStatusBar(self.statusbar)
self.retranslateUi(ArmcForm1)
QtCore.QMetaObject.connectSlotsByName(ArmcForm1)
def retranslateUi(self, ArmcForm1):
_translate = QtCore.QCoreApplication.translate
ArmcForm1.setWindowTitle(_translate("ArmcForm1", "MainWindow"))
self.label.setText(_translate("ArmcForm1", "运行内容显示框"))
self.label_2.setText(_translate("ArmcForm1", "进度:"))
self.label_11.setText(_translate("ArmcForm1", "读取数据和话题地址"))
self.label_30.setText(_translate("ArmcForm1", "Pub_qq:"))
self.lineEdit_sub_f.setText(_translate("ArmcForm1", "/ft_sensor_topic"))
self.label_12.setText(_translate("ArmcForm1", "Sub_F:"))
self.label_13.setText(_translate("ArmcForm1", "Sub_qq:"))
self.lineEdit_sub_qq.setText(_translate("ArmcForm1", "/armc/joint_states"))
self.lineEdit_pub_qq.setText(_translate("ArmcForm1", "/armc/joint_positions_controller/command"))
self.button_receive.setText(_translate("ArmcForm1", "接收机器人状态"))
self.label_4.setText(_translate("ArmcForm1", "q4:"))
self.lineEdit_q5.setText(_translate("ArmcForm1", "0"))
self.label_5.setText(_translate("ArmcForm1", "q6:"))
self.lineEdit_q6.setText(_translate("ArmcForm1", "0"))
self.label_6.setText(_translate("ArmcForm1", "q7:"))
self.lineEdit_q7.setText(_translate("ArmcForm1", "0"))
self.lineEdit_q4.setText(_translate("ArmcForm1", "0"))
self.label_7.setText(_translate("ArmcForm1", "q5:"))
self.label_3.setText(_translate("ArmcForm1", "给定关节角q/°"))
self.label_8.setText(_translate("ArmcForm1", "q3:"))
self.lineEdit_q3.setText(_translate("ArmcForm1", "0"))
self.label_9.setText(_translate("ArmcForm1", "q2:"))
self.lineEdit_q2.setText(_translate("ArmcForm1", "0"))
self.label_10.setText(_translate("ArmcForm1", "q1:"))
self.lineEdit_q1.setText(_translate("ArmcForm1", "0"))
self.button_wish_pos.setText(_translate("ArmcForm1", "目标点"))
self.button_begin.setText(_translate("ArmcForm1", "开始"))
self.button_stop.setText(_translate("ArmcForm1", "停止"))
self.checkBox_vel.setText(_translate("ArmcForm1", "速度勾 位置默认"))
self.checkBox_gazebo.setText(_translate("ArmcForm1", "仿真勾 实物默认"))
self.button_plan.setText(_translate("ArmcForm1", "规划"))