话题是一种单向通讯方式,它通过发布和订阅的方式传递消息,该模型涉及到三个角色:
Master 负责保管 Publisher 和 Subscriber 的注册信息,并匹配话题相同的 Publisher 和 Subscriber ,帮助 他们建立连接,连接建立后,Publisher 可以发布消息,且发布的消息会被 Subscriber 订阅。
话题模型通讯流程:
发布者(Publisher)向管理者(Master)注册信息,包括RPC地址和Topic名字。Master会将发布者的注册信息加入到注册表中,并查询是否有该话题的订阅者。
订阅者(Subscriber)向管理者(Master)注册信息,包括Topic名字。Master会将订阅者(Subscriber)的注册信息加入到注册表中,并查询是否有该话题的发布者。
管理者(Master)通过查询注册表发现有匹配的发布者(Publisher)和订阅者(Subscriber),则向订阅者(Subscriber)发送发布者的RPC地址信息。
订阅者根据发布者的RPC地址,请求连接发布者(Publisher),并传输订阅的话题名称、消息类型以及通信协议(TCP/UDP)。
4)发布者确认请求
发布者(Publisher)收到请求后,通过RPC向订阅者确认连接信息,并发送自身的 TCP/UDP 地址信息。
5)建立连接
订阅者根据发布者的TCP/UDP地址信息与订阅者建立TCP/UDP连接。
连接建立后,发布者开始向订阅者发布话题消息数据。
Note:
- 上述实现流程中,前五步使用 RPC 协议,最后两步使用 TCP/UDP 协议,默认TCP。
- 发布者 与 订阅者 的启动无先后顺序要求。
- 发布者 与 订阅者 都可以有多个。
- 发布者 与 订阅者 连接建立后,不再需要 ROS Master。即便关闭 ROS Master,发布者 与 订阅者 照常通信。不过不会再有新的发布者 与 订阅者加入。
万物始于Hello World,同样,使用Hello World介绍Topic的简单使用。
使用Topic传输数据时,需要注意以下几点:
接下来实现一个简单的 Topic
话题通信,发布者发布 Hello Word n
(n代表递增数列)字符串,订阅者接收到后输出到屏幕。
(这一步不是必须,这里只是为了方便清晰的说明,也可以使用已有的包,在包里新增节点等方法)
首先创建 topic_hello_world
包,命令如下:
catkin_creat_pkg topic_hello_world std_msgs roscpp rospy
创建后,文件结构如下:
Topic名称:/hello_world_topic
消息格式:std_msgs::String
消息文件路径:/opt/ros/noetic/share/std_msgs/msg/String.msg
消息文件内容:
string data
在创建的 topic_hello_world
包路径下有一个 src
目录,在这里存储C++源码,我们创建 topic_hello_world_pub.cpp
以实现发布者,编辑内容如下:
/*
实现流程:
1.包含头文件
2.初始化 ROS 节点:命名(唯一)
3.实例化 ROS 句柄
4.实例化 发布者 对象
5.组织被发布的数据,并编写逻辑发布数据
*/
// 1.包含头文件
#include "ros/ros.h"
#include "std_msgs/String.h" // std_msgs包自带的普通文本的消息类型
#include
int main(int argc, char **argv)
{
// 以下任意一句: 设置编码,解决ROS LOG打印中文乱码的问题
// 但 rostopic echo 中文乱码的问题无法解决
// setlocale(LC_ALL, "");
setlocale(LC_CTYPE, "zh_CN.utf8");
// 2.初始化 ROS 节点: 命名(唯一)
// 参数1和参数2 后期为节点传值会使用
// 参数3 是节点名称,是一个标识符,需要保证运行后,在 ROS 拓扑网络中唯一
ros::init(argc, argv, "publisher");
// 3.实例化 ROS 句柄
// 该类封装了 ROS 中的一些常用功能
ros::NodeHandle nh;
// 4.实例化 发布者 对象,向ROS Master注册发布者
// 泛型 std_msgs::String: 发布的消息类型
// 参数1: 要发布到的话题名称
// 参数2: 队列中最大保存的消息数,超出此阀值时,先进的先销毁(时间早的先销毁)
ros::Publisher pub = nh.advertise<std_msgs::String>("/hello_world_topic", 10);
// 延时1s等待publisher在ROS Master注册成功后,再发布消息。
// ros::Duration(1.0).sleep();
// 目的同上,为了确保发布者注册成功再发布消息
// 等待直到发布者成功注册到 ROS Master,并有订阅者订阅
while (pub.getNumSubscribers() == 0)
{
if (!ros::ok())
{
// 如果节点被关闭,退出程序
return 0;
}
ROS_INFO_ONCE("Waiting for subscribers to connect...");
ros::Duration(1.0).sleep(); // 等待一秒钟
}
// 5.组织被发布的数据,并编写逻辑发布数据
std_msgs::String msg;
std::string msg_front = "Hello World "; // 消息前缀
int count = 0; // 消息计数器
// 运行loop的频率(1Hz: 一秒1次)
ros::Rate r(1);
// 让节点一直运行
while (ros::ok())
{
// 拼接字符串与编号,并组装消息数据
msg.data = msg_front + std::to_string(count);
// 发布消息
pub.publish(msg);
// 打印发送的消息
ROS_INFO("发送的消息: %s", msg.data.c_str());
// 根据前面制定的发布频率自动休眠 休眠时间 = 1/频率 s;
r.sleep();
// 循环结束前,让 count 自增
count++;
}
return 0;
}
创建 topic_hello_world_sub.cpp
以实现订阅者,编辑内容如下:
/*
实现流程:
1.包含头文件
2.初始化 ROS 节点:命名(唯一)
3.实例化 ROS 句柄
4.实例化 订阅者 对象
5.处理订阅的消息(回调函数)
6.设置循环调用回调函数
*/
// 1.包含头文件
#include "ros/ros.h"
#include "std_msgs/String.h"
// 5.处理订阅的消息(回调函数)
// topic回调函数,处理订阅的消息
void topicCallback(const std_msgs::String::ConstPtr &msg_p)
{
ROS_INFO("收到的消息: %s", msg_p->data.c_str());
}
int main(int argc, char **argv)
{
// 以下任意一句: 设置编码,解决ROS LOG打印中文乱码的问题
// 但 rostopic echo 中文乱码的问题无法解决
// setlocale(LC_ALL, "");
setlocale(LC_CTYPE, "zh_CN.utf8");
// 2.初始化 ROS 节点:命名(唯一)
ros::init(argc, argv, "subscriber");
// 3.实例化 ROS 句柄
ros::NodeHandle nh;
// 4.实例化 订阅者 对象
ros::Subscriber sub = nh.subscribe<std_msgs::String>("/hello_world_topic", 10, topicCallback);
// 6.设置循环调用回调函数
ros::spin(); // 循环读取接收的数据,并调用回调函数处理
return 0;
}
修改 CMakeLists.txt
,只需添加如下内容:
add_executable(${PROJECT_NAME}_pub src/topic_hello_world_pub.cpp)
add_executable(${PROJECT_NAME}_sub src/topic_hello_world_sub.cpp)
target_link_libraries(${PROJECT_NAME}_pub
${catkin_LIBRARIES}
)
target_link_libraries(${PROJECT_NAME}_sub
${catkin_LIBRARIES}
)
编译运行
进入工作空间执行 catkin_make
命令编译工程,编译成功后,使用如下命令依次启动发布者和订阅者。
1. 启动ros master
roscore
2. 启动发布者
./devel/lib/topic_hello_world/topic_hello_world_pub
3. 启动订阅者
./devel/lib/topic_hello_world/topic_hello_world_sub
结果如下:
目前为止,Topic Hello World 已经成功了。
在创建的 topic_hello_world
包路径下 src
目录的同级,创建一个 scripts
目录,在这里存储脚本(如python脚本),我们创建 topic_hello_world_pub.py
以实现发布者,编辑内容如下:
#! /usr/bin python
"""
实现流程:
1.导包
2.初始化 ROS 节点:命名(唯一)
3.实例化 发布者 对象
4.组织被发布的数据,并编写逻辑发布数据
"""
# 1.导包
import rospy
from std_msgs.msg import String
def main():
# 2.初始化 ROS 节点:命名(唯一)
rospy.init_node("publisher")
# 3.实例化 发布者 对象
pub = rospy.Publisher("/hello_world_topic", String, queue_size=10)
# rospy.sleep(1)
while pub.get_num_connections() == 0:
if rospy.is_shutdown():
return
rospy.loginfo_once("Waiting for subscribers to connect...")
rospy.sleep(1)
# 4.组织要发布的数据,并编写逻辑发布数据
msg = String() # 创建 msg 对象
msg_front = "Hello World "
count = 0 # 计数器
# 设置循环频率
rate = rospy.Rate(1)
while not rospy.is_shutdown():
# 拼接字符串
msg.data = msg_front + str(count)
pub.publish(msg)
rate.sleep()
rospy.loginfo("发送的消息: %s", msg.data)
count += 1
if __name__ == "__main__":
main()
在scrips
中创建 topic_hello_world_sub.py
以实现订阅者,编辑内容如下:
#! /usr/bin python
"""
实现流程:
1.导包
2.初始化 ROS 节点:命名(唯一)
3.实例化 订阅者 对象
4.处理订阅的消息(回调函数)
5.设置循环调用回调函数
"""
# 1.导包
import rospy
from std_msgs.msg import String
# 4.处理订阅的消息(回调函数)
def topicCallback(msg):
rospy.loginfo("收到的消息: %s", msg.data)
def main():
# 2.初始化 ROS 节点:命名(唯一)
rospy.init_node("subscriber")
# 3.实例化 订阅者 对象
sub = rospy.Subscriber("/hello_world_topic", String, topicCallback, queue_size=10)
# 5.设置循环调用回调函数
rospy.spin()
if __name__ == "__main__":
main()
修改 CMakeLists.txt
,只需添加如下内容:
catkin_install_python(PROGRAMS
scripts/topic_hello_world_pub.py
scripts/topic_hello_world_sub.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
编译运行
进入工作空间执行 catkin_make
命令编译工程,编译成功后,使用如下命令依次启动发布者和订阅者。
1. 启动ros master(如果已启动,无需再启动)
roscore
2. 启动发布者
python ./devel/lib/topic_hello_world/topic_hello_world_pub.py
3. 启动订阅者
python ./devel/lib/topic_hello_world/topic_hello_world_pub.py
结果如下:
启动发布者与订阅者时建议用如下命令:(上述命令只是给初学者的):
启动发布者
rosrun topic_hello_world topic_hello_world_pub (C++版)
rosrun topic_hello_world topic_hello_world_pub.py (Python版)
启动订阅者
rosrun topic_hello_world topic_hello_world_sub (C++版)
rosrun topic_hello_world topic_hello_world_sub.py (Python版)
其中,rosrun
是执行ROS可执行文件的命令,topic_hello_world
是功能包的名称,topic_hello_world_pub
是该功能包下可执行文件(如节点)的名称。
如果你遇到如下错误:
那么可能你没有把工作空间的路径加到终端环境变量中,听起看来是不是很晕,不要急,catkin
为我们提供了一个脚本可以做这件事,它位于工作空间下的 devel
目录中,有如下三个脚本:
setup.bash
setup.zsh
setup.sh
其中,
source devel/setup.sh
命令时,它会将当前工作空间的路径添加到ROS_PACKAGE_PATH
中,并设置其他与ROS运行时相关的环境变量,如:将当前工作空间的 bin
, lib
, include
和 share
文件夹添加到终端环境的 PATH
, LD_LIBRARY_PATH
, CMAKE_PREFIX_PATH
和 PYTHONPATH
变量中。这样,在执行 ROS 命令和使用 ROS 相关库时,终端将能够找到和访问这些文件夹中的内容。setup.sh
。setup.bash
,用于设置ROS软件包的环境变量。他调用了 setup.sh
。根据你使用的shell类型运行相应的脚本,我们一般把脚本加到终端配置文件中,以bash为例:
~/.bashrc
文件,将source
添加到文件中,一般添加到末尾,其中
代表setup.bash
文件的绝对路径。source ~/.bashrc
使修改生效。至此,再执行 rosrun topic_hello_world topic_hello_world_pub
就不会报错了。
setup.sh
调用。catkin_make run_tests
时,测试框架会将测试结果输出到这个目录。这些文件和目录是构建和测试过程中的临时文件和配置文件,它们会在ROS工作空间的生命周期内动态生成和修改。