工具使用-ROS中使用publisher、subscriber发布订阅topic

发布 : 2019-06-24 浏览 :

Publisher Node

不同于cpp文件一般存在package下的src文件夹, python文件一般存储在package下的scripts文件夹下。

1
2
3
4
roscd beginner_tutorials/scripts
vim talker.py # 新创建
# 或者
rosed beginner_tutorials talker.py # 如果已经存在

talker.py内容

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
#!/usr/bin/env python
import rospy # 一般使用python写脚本时,都需要导入该包
from std_msgs.msg import String # 定义了topic之间传递消息的格式

def talker():
rospy.init_node("talker", anonymous=True) # 初始化该进程 ,定义进程名 “talker”,将该进程注册到master上, anonymous=True保证进程名的唯一性,如果出现重名,会通过添加后缀方式避免
# talker这个名字可以自定义,但是不能包含‘/’符号
pub = rospy.Publisher("chatter", String, queue_size=10) #该进程发布的topic, topic名称为chatter, 发布消息的格式是String, 发布的最大数量
rate = rospy.Rate(10) # 发布消息的频率
while not rospy.is_shutdown():
hello_str = "hello world %s"%rospy.get_time() # 要发布的消息
rospy.loginfo(hello_str) # logger, 输出到屏幕、logger file以及rosout重定向
pub.pubish(hello_str) # 发布消息
rate.sleep() # 按给定的Hz sleep

if __name__=="__main__":
try:
talker()
except rospy.ROSInterruptException: # 该异常有rospy.sleep或者rospy。Rate。sleep被中断后抛出
pass

Subscriber Node

subscriber node同样是一个线程,它从master订阅消息。

1
2
roscd beginner_tutotials/scripts
vim listener.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
#!/usr/bin/env python
import rospy
from std.msgs import String

def callback(data): # 回调函数,当订阅消息到达时,调用处理消息的函数
rospy.loginfo(rospy.get_caller_id() + "I heard %s"%s data.data) # 输出消息

def listener():
rospy.init_node("listener", anonymous=True) # 当前node的名称
rospy.Subscriber("chatter", String, callback) # 订阅器订阅的topic是chatter, 类型string, 回调函数callback
rospy.spin() # 这个是个单独的线程,和callback线程不同,用于保持进程活着直到被shutdown

if __name__=="__main__":
listener()

注意callback接收的参数就是前面的消息类型,这里是String, 可以查看String的结构

1
rosmsg show std_msgs/msg

发现只有一个变量

string data

所以在callback中调用时使用data.data 调用

注意 需要修改脚本的权限

1
2
chmod +x talker.py
chmod +x listener.py

Building nodes

不只是cpp文件需要编译,这里的python脚本,同样需要使用catkin编译,从而能够保证message被编译和运行时调用。

1
2
cd ~/catkin_ws
catkin_make

extension

每个node其实可以创建publisher,也可以创建subscriber,这里我们重新回顾msg创建部分,写个小例子。

定义一个msg,包含两个float32类型, node1发布两个数,node2接收两个数进行处理串联程string类型,然后再次发布, node1再订阅cat string并显示。具体看代码更清晰。

1
2
roscd beginner_tutorials/msg
vim test_msg.msg

test_msg.msg文件内容

float32 a

float32 b

定义完msg之后,注意需要修改CMakeLists文件,

1
2
3
4
add_messafe_files(
FILES
test_msg.msg
)

分别定义两个node

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
#!/usr/bin/env python

import rospy
import random
from std_msgs.msg import String
from beginner_tutorials.msg import test_msg

def callback(data):
rospy.loginfo("receieve from node2 %s"%data.data)

def test_node1():
rospy.init_node('node1', anonymous=True)
pub = rospy.Publisher('topic12', test_msg, queue_size=10)
rate = rospy.Rate(10)
rospy.Subscriber("topic21", String, callback)
while not rospy.is_shutdown():
msg = test_msg()
msg.a = random.random()
msg.b = random.random()
pub.publish(msg)
rospy.loginfo('send a: %f, b: %f from node1 '%(msg.a, msg.b))
rate.sleep()

if __name__=="__main__":
try:
test_node1()
except rospy.ROSInterruptException:
pass
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
#!/usr/bin/env python
import rospy
from beginner_tutorials.msg import test_msg
from std_msgs.msg import String

def callback(data):
str_cat = '%f%f'%(data.a, data.b)
rospy.loginfo('data from node1: %s'%str_cat)

def test_node2():
rospy.init_node("node2", anonymous=True)
pub = rospy.Publisher("topic21", String, queue_size=10)
rate = rospy.Rate(10)
rospy.Subscriber("topic12", test_msg, callback)
while not rospy.is_shutdown():
msg_str = 'send msg from node2'
rospy.loginfo(msg_str)
pub.publish(msg_str)
rate.sleep()

if __name__=="__main__":
try:
test_node2()
except rospy.ROIInterruptException:
pass
1
2
3
4
5
6
roscd beginner_tutorials/scripts
chmod +x test_node1.py
chmod +x test_node2.py
cd ~/catkin_ws
catkin_make
roscore # 启动master

重新打开两个终端,分别启动两个node

1
rosrun beginner_tutorials test_node1
1
rosrun beginner_tutorials test_node2

显示结果:

results

本文作者 : zhouzongwei
原文链接 : http://yoursite.com/2019/06/24/ros-publisher-subscriber/
版权声明 : 本博客所有文章除特别声明外,均采用 CC BY-NC-SA 4.0 许可协议。转载请注明出处!

知识 & 情怀 | 赏或者不赏,我都在这,不声不响

微信扫一扫, 以资鼓励

微信扫一扫, 以资鼓励

支付宝扫一扫, 再接再厉

支付宝扫一扫, 再接再厉

留下足迹