机器人是一种高度复杂的系统性实现,在机器人上可能集成各种传感器(雷达、摄像头、GPS…)以及运动控制实现,为了解耦合,在ROS中每一个功能点都是一个单独的进程,每一个进程都是独立运行的。更确切的讲,ROS是进程(也称为Nodes)的分布式框架。 因为这些进程甚至还可分布于不同主机,不同主机协同工作,从而分散计算压力。不过随之也有一个问题: 不同的进程是如何通信的?也即不同进程间如何实现数据交换的?
ROS 中的基本通信机制主要有如下三种实现策略:
话题通信是ROS中使用频率最高的一种通信模式,话题通信是基于发布订阅模式的,也即:一个节点发布消息,另一个节点订阅该消息。话题通信的应用场景也极其广泛,比如下面一个常见场景:
机器人在执行导航功能,使用的传感器是激光雷达,机器人会采集激光雷达感知到的信息并计算,然后生成运动控制信息 驱动机器人底盘运动。
在上述场景中,就不止一次使用到了话题通信。
4. 以激光雷达信息的采集处理为例,在 ROS 中有一个节点需要时时的发布当前雷达采集到的数据,导航模块中也有节点会订阅并解析雷达数据。
5. 再以运动消息的发布为例,导航模块会根据传感器采集的数据时时的计算出运动控制信息并发布给底盘,底盘也可以有一个节点订阅运动信息并最终转换成控制电机的脉冲信号。
6. 以此类推,像雷达、摄像头、GPS… 等等一些传感器数据的采集,也都是使用了话题通信,换言之,话题通信适用于不断更新的数据传输相关的应用场景。
话题通信以发布订阅的方式实现不同节点之间数据交互的通信模式,用于不断更新的、少逻辑处理的数据传输场景。
话题通信模型中涉及到三个角色,分别是:
7. ROS Mater(管理者):负责保管Taker和Listener注册的信息,并匹配话题相同的 Talker 与 Listener,帮助 Talker 与 Listener 建立连接。
8. Talker(发布者):发布消息。
9. Listener(订阅者):接收Talker的消息。
整个话题通信的流程如下图所示:
具体步骤如下:
0、Talker注册。Talker启动后,会通过RPC在 ROS Master 中注册自身信息,其中包含所发布消息的话题名称。ROS Master 会将节点的注册信息加入到注册表中。
1、Listener注册。Listener启动后,也会通过RPC在 ROS Master 中注册自身信息,包含需要订阅消息的话题名。ROS Master 会将节点的注册信息加入到注册表中。
2、ROS Master实现信息匹配。ROS Master 会根据注册表中的信息匹配Talker 和 Listener,并通过 RPC 向 Listener 发送 Talker 的 RPC 地址信息。
3、Listener向Talker发送请求。Listener 根据接收到的 RPC 地址,通过 RPC 向 Talker 发送连接请求,传输订阅的话题名称、消息类型以及通信协议(TCP/UDP)。
4、Talker确认请求。Talker 接收到 Listener 的请求后,也是通过 RPC 向 Listener 确认连接信息,并发送自身的 TCP 地址信息。
5、Listener与Talker件里连接。Listener 根据步骤4 返回的消息使用 TCP 与 Talker 建立网络连接。
6、Talker向Listener发送消息。连接建立后,Talker 开始向 Listener 发布消息。
注意1:上述实现流程中,前五步使用的 RPC协议,最后两步使用的是 TCP 协议
注意2: Talker 与 Listener 的启动无先后顺序要求
注意3: Talker 与 Listener 都可以有多个
注意4: Talker 与 Listener 连接建立后,不再需要 ROS Master。也即,即便关闭ROS Master,Talker 与 Listern 照常通信。
需求: 编写发布订阅实现,要求发布方以10HZ(每秒10次)的频率发布文本消息,订阅方订阅消息并将消息内容打印输出。
流程:
1 发布方
/*
需求: 实现基本的话题通信,一方发布数据,一方接收数据,
实现的关键点:
1.发送方
2.接收方
3.数据(此处为普通文本)
PS: 二者需要设置相同的话题
消息发布方:
循环发布信息:HelloWorld 后缀数字编号
实现流程:
1.包含头文件
2.初始化 ROS 节点:命名(唯一)
3.实例化 ROS 句柄
4.实例化 发布者 对象
5.组织被发布的数据,并编写逻辑发布数据
*/
// 1.包含头文件
#include "ros/ros.h"
#include "std_msgs/String.h" //普通文本类型的消息
#include
int main(int argc, char *argv[])
{
//设置编码
setlocale(LC_ALL,"");
//2.初始化 ROS 节点:命名(唯一)
// 参数1和参数2 后期为节点传值会使用
// 参数3 是节点名称,是一个标识符,需要保证运行后,在 ROS 网络拓扑中唯一
ros::init(argc,argv,"talker");
//3.实例化 ROS 句柄
ros::NodeHandle nh;//该类封装了 ROS 中的一些常用功能
//4.实例化 发布者 对象
//泛型: 发布的消息类型
//参数1: 要发布到的话题
//参数2: 队列中最大保存的消息数,超出此阀值时,先进的先销毁(时间早的先销毁)
ros::Publisher pub = nh.advertise<std_msgs::String>("chatter",10);
//5.组织被发布的数据,并编写逻辑发布数据
//数据(动态组织)
std_msgs::String msg;
// msg.data = "你好啊!!!";
std::string msg_front = "Hello 你好!"; //消息前缀
int count = 0; //消息计数器
//逻辑(一秒10次)
ros::Rate r(1);
//节点不死
while (ros::ok())
{
//使用 stringstream 拼接字符串与编号
std::stringstream ss;
ss << msg_front << count;
msg.data = ss.str();
//发布消息
pub.publish(msg);
//加入调试,打印发送的消息
ROS_INFO("发送的消息:%s",msg.data.c_str());
//根据前面制定的发送贫频率自动休眠 休眠时间 = 1/频率;
r.sleep();
count++;//循环结束前,让 count 自增
//暂无应用
ros::spinOnce();
}
return 0;
}
2 订阅方
/*
需求: 实现基本的话题通信,一方发布数据,一方接收数据,
实现的关键点:
1.发送方
2.接收方
3.数据(此处为普通文本)
消息订阅方:
订阅话题并打印接收到的消息
实现流程:
1.包含头文件
2.初始化 ROS 节点:命名(唯一)
3.实例化 ROS 句柄
4.实例化 订阅者 对象
5.处理订阅的消息(回调函数)
6.设置循环调用回调函数
*/
// 1.包含头文件
#include "ros/ros.h"
#include "std_msgs/String.h"
void doMsg(const std_msgs::String::ConstPtr& msg_p){
ROS_INFO("我听见:%s",msg_p->data.c_str());
// ROS_INFO("我听见:%s",(*msg_p).data.c_str());
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
//2.初始化 ROS 节点:命名(唯一)
ros::init(argc,argv,"listener");
//3.实例化 ROS 句柄
ros::NodeHandle nh;
//4.实例化 订阅者 对象
ros::Subscriber sub = nh.subscribe<std_msgs::String>("chatter",10,doMsg);
//5.处理订阅的消息(回调函数)
// 6.设置循环调用回调函数
ros::spin();//循环读取接收的数据,并调用回调函数处理
return 0;
}
3 配置 CMakeLists.txt
add_executable(Hello_pub
src/Hello_pub.cpp
)
add_executable(Hello_sub
src/Hello_sub.cpp
)
target_link_libraries(Hello_pub
${catkin_LIBRARIES}
)
target_link_libraries(Hello_sub
${catkin_LIBRARIES}
)
4 执行
PS: 可以使用 rqt_graph 查看节点关系。
在 ROS 通信协议中,数据载体是一个较为重要组成部分,ROS 中通过 std_msgs 封装了一些原生的数据类型,比如:String、Int32、Int64、Char、Bool、Empty等。但是,这些数据一般只包含一个 data 字段,结构的单一意味着功能上的局限性,当传输一些复杂的数据,比如: 激光雷达的信息等。std_msgs 由于描述性较差而显得力不从心,这种场景下可以使用自定义的消息类型。
我们通过下面的任务来自定义消息。
需求: 创建自定义消息,该消息包含人的信息:姓名、身高、年龄等。
流程:
功能包下新建 msg 目录,添加文件 Person.msg
string name
uint16 age
float64 height
package.xml中添加编译依赖与执行依赖
message_generation
message_runtime
CMakeLists.txt编辑 msg 相关配置
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
# 需要加入 message_generation,必须有 std_msgs
## 配置 msg 源文件
add_message_files(
FILES
Person.msg
)
# 生成消息时依赖于 std_msgs
generate_messages(
DEPENDENCIES
std_msgs
)
#执行时依赖
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES demo02_talker_listener
CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
# DEPENDS system_lib
)
编译后的中间文件查看: C++ 需要调用的中间文件(…/工作空间/devel/include/包名/xxx.h),后续调用相关 msg 时,是从这些中间文件调用的。
编写发布订阅实现,要求发布方以10HZ(每秒10次)的频率发布自定义消息,订阅方订阅自定义消息并将消息内容打印输出。
为了方便代码提示以及避免误抛异常,需要先配置 vscode,将前面生成的 head 文件路径配置进 c_cpp_properties.json 的 includepath属性:
{
"configurations": [
{
"browse": {
"databaseFilename": "",
"limitSymbolsToIncludedHeaders": true
},
"includePath": [
"/opt/ros/noetic/include/**",
"/usr/include/**",
"/xxx/yyy工作空间/devel/include/**" //配置 head 文件的路径
],
"name": "ROS",
"intelliSenseMode": "gcc-x64",
"compilerPath": "/usr/bin/gcc",
"cStandard": "c11",
"cppStandard": "c++17"
}
],
"version": 4
}
/*
需求: 循环发布人的信息
*/
#include "ros/ros.h"
#include "demo02_talker_listener/Person.h"
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
//1.初始化 ROS 节点
ros::init(argc,argv,"talker_person");
//2.创建 ROS 句柄
ros::NodeHandle nh;
//3.创建发布者对象
ros::Publisher pub = nh.advertise<demo02_talker_listener::Person>("chatter_person",1000);
//4.组织被发布的消息,编写发布逻辑并发布消息
demo02_talker_listener::Person p;
p.name = "sunwukong";
p.age = 2000;
p.height = 1.45;
ros::Rate r(1);
while (ros::ok())
{
pub.publish(p);
p.age += 1;
ROS_INFO("我叫:%s,今年%d岁,高%.2f米", p.name.c_str(), p.age, p.height);
r.sleep();
ros::spinOnce();
}
return 0;
}
/*
需求: 订阅人的信息
*/
#include "ros/ros.h"
#include "demo02_talker_listener/Person.h"
void doPerson(const demo02_talker_listener::Person::ConstPtr& person_p){
ROS_INFO("订阅的人信息:%s, %d, %.2f", person_p->name.c_str(), person_p->age, person_p->height);
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
//1.初始化 ROS 节点
ros::init(argc,argv,"listener_person");
//2.创建 ROS 句柄
ros::NodeHandle nh;
//3.创建订阅对象
ros::Subscriber sub = nh.subscribe<demo02_talker_listener::Person>("chatter_person",10,doPerson);
//4.回调函数中处理 person
//5.ros::spin();
ros::spin();
return 0;
}
需要添加 add_dependencies 用以设置所依赖的消息相关的中间文件。
add_executable(person_talker src/person_talker.cpp)
add_executable(person_listener src/person_listener.cpp)
add_dependencies(person_talker ${PROJECT_NAME}_generate_messages_cpp)
add_dependencies(person_listener ${PROJECT_NAME}_generate_messages_cpp)
target_link_libraries(person_talker
${catkin_LIBRARIES}
)
target_link_libraries(person_listener
${catkin_LIBRARIES}
)
PS: 可以使用 rqt_graph 查看节点关系。