简易Python实现Qt
Node创建流程
1. python环境配置
为clion添加python2的支持,具体可以参考前面的讲解
在新建的py
文件开头添加环境说明:
| #!/usr/bin/env python
#coding:utf-8
|
修改新建py
文件的权限,添加可执行权限
2. node源码编写
| import rospy
if __name__ == '__main__':
nodeName = "turle_ctrl";
# 创建ros node
rospy.init_node(nodeName)
|
Qt UI的创建
1. Qt库的引入
| from PyQt5.QtWidgets import *
|
Warning
值得注意的是,在导入模块过程中是没有提示的。系统已经有Qt5的库,只是编译器没有找到。
2. 编写Qt窗体
| # 创建Qt程序
app = QApplication(sys.argv)
# 创建窗体
window = QWidget()
window.setWindowTitle("小乌龟控制")
window.resize(400, 0)
# 显示窗体
window.show();
# Qt程序执行
sys.exit(app.exec_())
|
Tip
值得注意的是后面的app.exec()
这个函数不能用,要用app.exec_()
。
原因是当前的Qt版本是5.5.1
, 5.10.+
的版本后面才支持的exec()
3. 根据需求进行UI布局
1
2
3
4
5
6
7
8
9
10
11
12 | # 布局
layout = QFormLayout()
window.setLayout(layout)
# 控件
editLinear = QLineEdit()
layout.addRow("线速度", editLinear)
editAngular = QLineEdit()
layout.addRow("角速度", editAngular)
btnSend = QPushButton("发送")
layout.addRow(btnSend)
|
4. 事件添加
| btnSend.clicked.connect(clickSend)
define clickSend():
print "clicked"
|
Publisher创建
1. 确定消息传递的数据类型
通过rostopic命令查询主题对应的消息类型
| rostopic type /turtle1/cmd_vel
|
得到的结果为geometry_msgs/Twist
接下来我们需要导入这个消息类型对应的模块到py
文件中
| from geometry_msgs.msg import Twist
|
Tip
一些规律的掌握,消息类型为geometry_msgs/Twist
,需要导入的模块为geometry_msgs.msg
下的Twist
2. 创建publisher对象
| publisher = rospy.Publisher(topicName, Twist, queue_size=1000)
|
Tip
值得注意的是,在创建publisher对象时,这里要去确定的有两个点,第一就是topicName,第二就是传递的消息类型。
给小乌龟发送数据的topic为/turtle1/cmd_vel
类型为Twist
3. 发送消息
| # 创建消息
twist = Twist()
# 填充数据
twist.linear.x = linearX
twist.angular.z = angluarZ * math.pi / 180
# 发送消息
publisher.publish(twist)
|
完整示例代码
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57 | #!/usr/bin/env python
# coding:utf-8
import sys
import rospy
from PyQt5.QtWidgets import *
from geometry_msgs.msg import Twist
from math import radians
def clickSend(editLinear, editAngular, publisher):
linearX = float(editLinear.text())
angluarZ = float(editAngular.text())
# 创建消息
twist = Twist()
# 填充数据
twist.linear.x = linearX
twist.angular.z = radians(angluarZ)
# 发送消息
publisher.publish(twist)
if __name__ == '__main__':
nodeName = "turtle_ctrl"
rospy.init_node(nodeName)
# 创建publisher
topicName = "/turtle1/cmd_vel"
publisher = rospy.Publisher(topicName, Twist, queue_size=1000)
# 创建程序
app = QApplication(sys.argv)
window = QWidget()
window.resize(400, 120)
window.setWindowTitle("小乌龟控制")
# 布局
layout = QFormLayout()
window.setLayout(layout)
# 控件
editLinear = QLineEdit()
layout.addRow("线速度", editLinear)
editAngular = QLineEdit()
layout.addRow("角速度", editAngular)
btnSend = QPushButton("发送")
layout.addRow(btnSend)
# 事件
btnSend.clicked.connect(lambda: clickSend(editLinear, editAngular, publisher))
window.show()
sys.exit(app.exec_())
|