ROS with python GUI(tkinter)

简单的例子:

  • 用两个按钮控制气泵 开启,关闭
  • 用一个滑块控制舵机旋转角度

接线部分:


实际

Arduino部分的代码

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
#include <ros.h>
#include <std_msgs/String.h>
#include <std_msgs/UInt16.h>
#include <Servo.h>
ros::NodeHandle nh;

int PumpPin = 4;
Servo servo;

void pump_cb(const std_msgs::String& cmd_msg) {
if (strcmp(cmd_msg.data,"begin")==0) {
//如果接收到的String为begin,则开启气泵
digitalWrite(PumpPin, HIGH);
//如果接收到的String为stop,则关闭气泵
}
if (strcmp(cmd_msg.data,"stop")==0) {
digitalWrite(PumpPin, LOW);
}
}

void servo_cb(const std_msgs::UInt16& cmd_msg){
servo.write(cmd_msg.data);
}

ros::Subscriber<std_msgs::String> sub("pump", pump_cb);
//订阅pump这个topic,调用pump_cb这个回调函数
ros::Subscriber<std_msgs::UInt16> sub2("servo", servo_cb);
//订阅servo这个topic,调用servo_cb这个回调函数

void setup() {
// put your setup code here, to run once:
pinMode(PumpPin, OUTPUT);
servo.attach(8);
nh.initNode();
nh.subscribe(sub);
nh.subscribe(sub2);
}

void loop() {

nh.spinOnce();
delay(1);

}

将代码上传Arduino后,启动rosserial。


开启另一个终端,查看所有topic,里面已经有pump和servo这两个topic了。

此时直接使用rostopic pub发布相应的message给这两个topic,就能操纵气泵开启关闭,以及控制舵机旋转角度了。

Python部分

tkinter是Python自带的GUI库,使用起来非常简单,在这一部分需要点下按钮向之前的那两个topic发送相应的信息。

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
import rospy
import tkinter as tk
from std_msgs.msg import String
from std_msgs.msg import UInt16

pub = rospy.Publisher('pump', String, queue_size=10)
servo_pub = rospy.Publisher('servo', UInt16, queue_size=10)
//创建两个publisher,分别往之前的那两个topic发送不同数据类型的消息

def start():
pub.publish("begin")


def stop():
pub.publish("stop")


def talker():
rospy.init_node('pump_controller', anonymous=True)
rate = rospy.Rate(10)


def servo_publisher(v):
servo_pub.publish(int(v))//因为传过来的v是char,所以publish之前要先转换成int

root = tk.Tk()//root窗口

btnPumpStart = tk.Button(root, text="pump start", command=start)
btnPumpStop = tk.Button(root, text="pump stop", command=stop)
btnPumpStart.pack()
btnPumpStop.pack()

servoScale = tk.Scale(root, label='servo', from_=0, to='180', orient=tk.HORIZONTAL, length=400, showvalue=1,
tickinterval=20, resolution=1, command=servo_publisher)
servoScale.pack()
if __name__ == '__main__':
try:
talker()
root.mainloop()
except rospy.ROSInterruptException:
pass

运行后会出现两个按钮和一个滑动条
使用echo可以看到确实发送了这些信息

点击按钮可以控制气泵开启关闭(也就是控制那个继电器),滑动滑块可以控制舵机旋转角度,非常直观,也没什么延迟。