ROS Topic¶
ROS Topic概念¶
ROS Node之间进行通信所利用的最重要的机制就是消息传递,在ROS中,消息有组织的放到Topic里进行传递。
Publisher
- 生成信息,通过ROS Topic与其它Node进行通信。
- 通常用于处理原始的传感器信息,如相机、编码器等。
Subscriber
- 接收信息,通过ROS Topic接收来自其它Node的信息,并通过回调函数处理
- 通常用于监测系统状态,如当机器人关节到达限位位置时触发运动中断
Topic通信过程为:
- Publisher节点和Subscriber节点分别在Master进行注册
- Publisher发布Topic
- Subscriber在Master指挥下订阅Topic,从而建立起Pub-Sub之间的通信
注意:消息是直接从发布节点传递到订阅节点,并不经过Master。
下图是ROS Node和ROS Topic概念的图形化表示,我们可以看到两个Node(圆形)通过Topic(长方形)实现通信。
Topic通信的特点为:
1. Topic通信是多对多的异步通信方式:
Topic Publisher调用publish()方法发布消息,发送完立即返回,不用等待反馈;Subscriber通过回调函数的方式来处理消息。
对于同一Topic,系统中可以同时存在多个Publisher和多个Subscriber;
另外,Publisher并不知道哪个节点会接收消息,而Subscriber也并不知道接收的消息来自哪个节点,节点之间是松耦合的,这也是ROS最关键的设计特性之一。
2. 对于实时性、周期性的消息,使用topic传输是最佳的选择
3. Topic通信方式充分体现了分布式系统通信的好处:扩展性好,软件复用率高
ROS Topic命令行工具¶
ROS提供了一些命令行工具帮助我们查看Topic的信息,最常用的是:
rostopic list #列出当前正在运行的Topics
rostopic info <topic_name> #查看指定Topic的信息
rostopic echo <topic_name> #打印指定Topic的内容
更多ROS Topic的命令行工具可通过在终端中输入 rostopic -h
查看
ROS Topic示例¶
Publisher Node Demo
#!/usr/bin/python2
# coding: utf-8
import rospy #导入ROS Python客户端
from std_msgs.msg import String
def simplePublisher():
rospy.init_node('publish_node', anonymous = False) #初始化ROS节点
simple_publisher = rospy.Publisher('simple_topic', String, queue_size = 10) #定义Publisher对象
rate = rospy.Rate(10) #设置Topic发布的频率(Hz)
simple_topic_content = "simple pub-sub demo" #填充Topic内容
while not rospy.is_shutdown():
simple_publisher.publish(simple_topic_content) #发布Topic
rate.sleep() #确保Topic以我们设定的频率发布
if __name__ == '__main__':
try:
simplePublisher()
except rospy.ROSInterruptException:
pass
Subscriber Node Demo
#!/usr/bin/python
# coding: utf-8
import rospy #导入ROS Python客户端
from std_msgs.msg import String
# 定义Subscriber回调函数,处理收到的信息
def stringSubscriberCallback(data): #data的数据类型与Subscriber接收的Topic对应的消息类型一致
rospy.loginfo('The contents of simple_topic: %s', data.data)
def stringSubscriber():
rospy.init_node('subscribe_node', anonymous = False) #初始化ROS节点
rospy.Subscriber('simple_topic', String, stringSubscriberCallback) #定义Subscriber对象
rospy.spin()
if __name__ == '__main__':
stringSubscriber()
自定义Message类型¶
Topic类型严格来说是一个抽象的概念,提到Topic类型,通常指的是Node通过Topic传递的Message的类型。
ROS提供了大量的标准Message类,同时也支持用户自定义Message类型。
Message文件
- ROS通过message文件定义Message
- Message文件通常位于<ros_package_name>/msg文件夹中
- Message文件的名字通常为<custom_message_type>.msg
自定义Message类型
现在,我们定义一个新的超声传感器类型: UltrasoundInformation
要求包含:
- ROS message type - 距离传感器接口类型
- String - 超声传感器制造商名称
- Unsigned Integer - 超声传感器编号
我们可以通过以下指令创建这个新的Message类型:
首先创建msg文件:
roscd topic_demo
mkdir msg
cd msg
touch UltrasoundInformation.msg
然后在新建的msg文件中输入以下内容:
sensor_msgs/Range distance
string maker_name
uint32 part_number
编译构建自定义的Message类型
在上一部分我们定义了新的Message文件,新定义的Message经过编译构建之后才能在程序中使用。
首先修改package.xml文件,在package.xml文件中添加以下内容:
<build_depend>sensor_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>message_generation</build_export_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>message_runtime</exec_depend>
然后修改CMakeLists.txt文件,在CMakeLists.txt文件中相应的位置添加以下内容:
# 在find_package中添加sensor_msgs, message_generation
find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
sensor_msgs
message_generation
)
# 在add_message_files中添加UltrasoundInformation.msg
add_message_files(
FILES
UltrasoundInformation.msg
)
# 在generate_messages中添加sensor_msgs
generate_messages(
DEPENDENCIES
std_msgs
sensor_msgs
)
随后切换到tr_tutorial_ws顶层目录执行编译构建:
catkin build
编译完成之后:
source devel/setup.bash
我们可以通过 rosmsg 命令行工具查看新定义的Message类型:
rosmsg show topic_demo/UltrasoundInformation
# 新定义的Message的内容
sensor_msgs/Range distance
uint8 ULTRASOUND=0
uint8 INFRARED=1
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint8 radiation_type
float32 field_of_view
float32 min_range
float32 max_range
float32 range
string maker_name
uint32 part_number
如果想查看更详细的描述,可以添加 -r 命令选项:
rosmsg show topic_demo/UltrasoundInformation -r
这样我们就可以在程序中使用自定义的Message类型了。
ROS Topic练习¶
我们已经完成了Publisher、Subscriber的构建及定义新的Message类型,接下来我们进行一个小练习,构建一个简单的ROS应用:
- 包含一个Publisher和一个Subscriber
- Publisher发布新定义的Message类型
- Subscriber接收到新定义的Message类型之后反馈接收结果
ROS Topic练习示例-Publisher:
#!/usr/bin/python2
# coding: utf-8
import rospy
from topic_demo.msg import UltrasoundInformation
def ultrasoundPublisher():
rospy.init_node('ultra_publish_node', anonymous = False)
ultra_publisher = rospy.Publisher('ultra_topic', UltrasoundInformation, queue_size =10)
rate = rospy.Rate(10)
ultra_information = UltrasoundInformation()
ultra_information.distance.header.stamp = rospy.Time.now()
ultra_information.distance.header.frame_id = 'ultrasound_frame'
ultra_information.distance.radiation_type = 0
ultra_information.distance.field_of_view = 0.05
ultra_information.distance.min_range = 0.01
ultra_information.distance.max_range = 0.1
ultra_information.maker_name = 'tony_robotics'
ultra_information.part_number = 100
while not rospy.is_shutdown():
ultra_publisher.publish(ultra_information)
rate.sleep()
if __name__ == '__main__':
try:
ultrasoundPublisher()
except rospy.ROSInterruptException:
pass
ROS Topic练习示例-Subscriber:
#!/usr/bin/python2
# coding: utf-8
import rospy
from topic_demo.msg import UltrasoundInformation
def ultrasoundSubscriberCallback(data):
rospy.loginfo('The distance form ultrasound sensor is: %f', data.distance.field_of_view)
def ultrasoundSubscriber():
rospy.init_node('ultra_subscribe_node', anonymous = False)
rospy.Subscriber('ultra_topic', UltrasoundInformation, ultrasoundSubscriberCallback)
rospy.spin()
if __name__ == '__main__':
ultrasoundSubscriber()
更多关于ROS Message的资料可参考以下链接:
关于如何创建自定义的Message类型的内容可参考以下链接: