Skip to content

Commit 03a240a

Browse files
committed
add: 12.话题消息的定义与使用(python有error)
1 parent 1b8e10f commit 03a240a

File tree

3 files changed

+72
-0
lines changed

3 files changed

+72
-0
lines changed

catkin_wp/devel/lib/python2.7/dist-packages/learning_topic/__init__.py

Whitespace-only changes.
Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
#!/usr/bin/env python
2+
# -*- coding: utf-8 -*-
3+
4+
########################################################################
5+
#### Copyright 2020 GuYueHome (www.guyuehome.com). ###
6+
########################################################################
7+
8+
# 该例程将发布/person_info话题,自定义消息类型learning_topic::Person
9+
10+
import rospy
11+
from learning_topic.msg import Person
12+
13+
14+
def velocity_publisher():
15+
# ROS节点初始化
16+
rospy.init_node('person_publisher', anonymous=True)
17+
18+
# 创建一个Publisher,发布名为/person_info的topic,消息类型为learning_topic::Person,队列长度10
19+
person_info_pub = rospy.Publisher('/person_info', Person, queue_size=10)
20+
21+
#设置循环的频率
22+
rate = rospy.Rate(10)
23+
24+
while not rospy.is_shutdown():
25+
# 初始化learning_topic::Person类型的消息
26+
person_msg = Person()
27+
person_msg.name = "Tom"
28+
person_msg.age = 18
29+
person_msg.sex = Person.male
30+
31+
# 发布消息
32+
person_info_pub.publish(person_msg)
33+
rospy.loginfo("Publsh person message[%s, %d, %d]",
34+
person_msg.name, person_msg.age, person_msg.sex)
35+
36+
# 按照循环频率延时
37+
rate.sleep()
38+
39+
40+
if __name__ == '__main__':
41+
try:
42+
velocity_publisher()
43+
except rospy.ROSInterruptException:
44+
pass
Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
#!/usr/bin/env python
2+
# -*- coding: utf-8 -*-
3+
4+
########################################################################
5+
#### Copyright 2020 GuYueHome (www.guyuehome.com). ###
6+
########################################################################
7+
8+
# 该例程将订阅/person_info话题,自定义消息类型learning_topic::Person
9+
10+
import rospy
11+
from learning_topic.msg import Person
12+
13+
def personInfoCallback(msg):
14+
rospy.loginfo("Subcribe Person Info: name:%s age:%d sex:%d",
15+
msg.name, msg.age, msg.sex)
16+
17+
def person_subscriber():
18+
# ROS节点初始化
19+
rospy.init_node('person_subscriber', anonymous=True)
20+
21+
# 创建一个Subscriber,订阅名为/person_info的topic,注册回调函数personInfoCallback
22+
rospy.Subscriber("/person_info", Person, personInfoCallback)
23+
24+
# 循环等待回调函数
25+
rospy.spin()
26+
27+
if __name__ == '__main__':
28+
person_subscriber()

0 commit comments

Comments
 (0)