该模型中涉及到三个角色:
ROS Master 负责保管
Talker 和 Listener 注册的信息
,并匹配话题相同的 Talker 与 Listener
,帮助 Talker 与 Listener 建立连接
,连接建立后,Talker 可以发布(Publish)
消息,且发布的消息会被 Listener 订阅(Subscribe)
。
整个流程由以下步骤实现:
1.Talker注册
Talker启动后,会通过RPC在 ROS Master 中注册自身信息,其中包含所发布消息的话题名称。ROS Master 会将节点的注册信息加入到注册表中。
2.Listener注册
Listener启动后,也会通过RPC在 ROS Master 中注册自身信息,包含需要订阅消息的话题名。ROS Master 会将节点的注册信息加入到注册表中。
3.ROS Master实现信息匹配
ROS Master 会根据注册表中的信息匹配Talker 和 Listener,并通过 RPC 向 Listener 发送 Talker 的 RPC 地址信息。
4.Listener向Talker发送请求
Listener 根据接收到的 RPC 地址,通过 RPC 向 Talker 发送连接请求,传输订阅的话题名称、消息类型以及通信协议(TCP/UDP)。
5.Talker确认请求
Talker 接收到 Listener 的请求后,也是通过 RPC 向 Listener 确认连接信息,并发送自身的 TCP 地址信息。
6.Listener与Talker件里连接
Listener 根据步骤4 返回的消息使用 TCP 与 Talker 建立网络连接。
7.alker向Listener发送消息
连接建立后,Talker 开始向 Listener 发布消息。
注意1: Talker 与 Listener 的启动无先后顺序要求
注意2: Talker 与 Listener 都可以有多个
注意3: Talker 与 Listener 建立连接后,不再需要 ROS Master即便关闭ROS Master,Talker 与 Listern 可以照常通信。
实现效果:Talker发布方以固定频率发送一段文本,Listener订阅方接收文本并输出。
首先新建一个工作空间"pub_sub_workspace"
然后新建一个功能包"pub_sub_pkg"
然后新建一个发布方的实现代码"mypub.cpp"
#include "ros/ros.h"
#include "std_msgs/String.h"
/*
发布方实现:
1.包含头文件:ROS中的文本类型 ---> std_msgs/String.h
2.初始化ROS节点;
3.创建节点句柄;
4.创建发布者对象;
5.编写发布逻辑并发布数据。
*/
int main(int argc, char *argv[])
{
//初始化节点名为:seu666
ros::init(argc,argv,"seu666");
//创建句柄seuNB,用来管理资源
ros::NodeHandle seuNB;
//用Publisher类,实例化一个发布者对象yao,发布一个名为"BurgerKing"的话题,话题的消息类型为std_msgs::String,消息发布队列长度为10(注意话题名中间不能有空格)
ros::Publisher yao = seuNB.advertise<std_msgs::String>("BurgerKing",10);
//发布逻辑and发布数据
//先创建被发布的消息:创建一个一个String类型的变量msg2333
std_msgs::String msg2333;
//编写循环,循环发布数据
while(ros::ok())
{
msg2333.data = "good good good";
yao.publish(msg2333); //将消息发布出去
}
return 0;
}
节点名:seu666(注意节点名中间不能有空格,否则rosrun会报错)
话题名:BurgerKing(注意话题名中间不能有空格,否则rosrun会报错)
src/C++源文件的名称:mypub
为了方便,一般会令可执行文件的名称=src/C++源文件的名称,所以这里都叫mypub
配置CMakeLists.txt
add_executable(mypub src/mypub.cpp)
target_link_libraries(mypub ${catkin_LIBRARIES})
Ctrl + Shift +B编译一下,看看有没有问题
新建一个终端
roscore
再新建一个终端,设置环境变量,启动节点rosrun <功能包名> <可执行文件名>
source devel/setup.bash
rosrun pub_sub_pkg mypub
没有任何日志输出,这是因为代码里发布的消息没有发布到终端,而是一直在等待订阅者接收
可以再开一个终端,显示话题的调试信息
# rostopic echo <话题名>:可以将<话题名>的话题的消息打印到终端
rostopic echo BurgerKing
可以看到节点seu666中的发布者对象yao疯狂发消息"good good good"
改进:发布逻辑不对,发的太快了,应该以特定频率发送,并且在文本后加编号,再增加一个日志输出
#include "ros/ros.h"
#include "std_msgs/String.h"
#include //C++中的用来进行数据类型转换的
/*
发布方实现:
1.包含头文件:ROS中的文本类型 ---> std_msgs/String.h
2.初始化ROS节点;
3.创建节点句柄;
4.创建发布者对象;
5.编写发布逻辑并发布消息。
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL, "");//设置编码:避免中文乱码
//初始化节点名为:seu666
ros::init(argc,argv,"seu666");
//创建句柄seuNB,用来管理资源
ros::NodeHandle seuNB;
//用Publisher类,实例化一个发布者对象yao,发布一个名为"BurgerKing"的话题,话题的消息类型为std_msgs::String,消息发布队列长度为10(注意话题名中间不能有空格)
ros::Publisher yao = seuNB.advertise<std_msgs::String>("BurgerKing",10);
//先创建被发布的消息:创建一个一个String类型的变量msg2333
std_msgs::String msg2333;
//发布频率:10Hz
ros::Rate rate(10);
//设置消息编号
int count = 0;
//编写循环,循环发布数据
while(ros::ok())
{
count++;
//msg2333.data = "good good good";
//实现字符串拼接数字
std::stringstream ss2333;
ss2333 <<"good good good--->" << count;
msg2333.data = ss2333.str(); //将ss2333流里面数据转换成字符串,并放到msg2333里头
yao.publish(msg2333); //将消息发布出去
//添加日志:顺便将发布的数据打印到终端,c_str()函数是String类中的一个函数,它返回当前字符串的首字符地址
ROS_INFO("发布的数据是:%s",ss2333.str().c_str()); //这里发布的日志中含义中文的,要避免乱码问题,可以在代码最前面加一句setlocale(LC_ALL, "");
rate.sleep();
}
return 0;
}
然后新建一个订阅方的实现代码"mysub.cpp"
#include "ros/ros.h"
#include "std_msgs/String.h"
/*
订阅方实现:
1.包含头文件:ROS中的文本类型 ---> std_msgs/String.h
2.初始化ROS节点;
3.创建节点句柄;
4.创建订阅者对象;
5.处理订阅到的消息;
*/
void mesg2333_callback(const std_msgs::String::ConstPtr &msg_p)//订阅到的消息是std_msgs::string类型,这个函数的参数类型是它的常量指针的引用
{
//通过msg获取订阅到的消息,并对它进行处理,即在终端中打印出来
ROS_INFO("seu666PLUS订阅的消息是:%s",msg_p->data.c_str());
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL, "");//设置编码:避免中文乱码
//初始化节点名为:seu666PLUS
ros::init(argc,argv,"seu666PLUS"); //一个工作空间中,节点名不能重复
//创建句柄seuNBPLUS,用来管理资源
ros::NodeHandle seuNBPLUS;
//用Subscriber类,实例化一个订阅者对象,订阅一个名为"BurgerKing"的话题,话题的消息类型为std_msgs::String,消息发布队列长度为10(注意话题名中间不能有空格)
ros::Subscriber yaoPLUS = seuNBPLUS.subscribe<std_msgs::String>("BurgerKing",10,mesg2333_callback); //订阅的话题名,队列长度,回调函数
//循环读取接收的数据,并调用回调函数处理:mesg2333_callback()每订阅到一次消息都需要执行一次,为了让回调函数多次执行,需要再执行完一次之后需要回头
ros::spin();
return 0;
}
节点名:seu666PLUS
话题名:BurgerKing
可执行文件的名称=src/C++源文件的名称,这里都叫mysub
配置CMakeLists.txt,增加下面两句
add_executable(mysub src/mysub.cpp)
target_link_libraries(mysub ${catkin_LIBRARIES})
保存、编译、运行、成功
新建一个终端
roscore
再新建一个终端,启动发布方节点
source devel/setup.bash
rosrun pub_sub_pkg mypub
再新建一个终端,启动订阅方节点
source devel/setup.bash
rosrun pub_sub_pkg mysub