服务通信也是ROS中一种极其常用的通信模式,服务通信是基于请求响应模式的,是一种应答机制。也即: 一个节点A向另一个节点B发送请求,B接收处理请求并产生响应结果返回给A。比如如下场景:
机器人巡逻过程中,控制系统分析传感器数据发现可疑物体或人... 此时需要拍摄照片并留存。
在上述场景中,就使用到了服务通信。
-
一个节点需要向相机节点发送拍照请求,相机节点处理请求,并返回处理结果
与上述应用类似的,服务通信更适用于对时时性有要求、具有一定逻辑处理的应用场景。
概念
以请求响应的方式实现不同节点之间数据交互的通信模式。
作用
用于偶然的、对时时性有要求、有一定逻辑处理需求的数据传输场景。
1 服务通信理论模型
服务通信较之于话题通信更简单些,理论模型如下图所示,该模型中涉及到三个角色:
-
ROS master(管理者)
-
Server(服务端)
-
Client(客户端)
ROS Master 负责保管 Server 和 Client 注册的信息,并匹配话题相同的 Server 与 Client ,帮助 Server 与 Client 建立连接,连接建立后,Client 发送请求信息,Server 返回响应信息。
整个流程由以下步骤实现:
(0).Server注册
Server 启动后,会通过RPC在 ROS Master 中注册自身信息,其中包含提供的服务的名称。ROS Master 会将节点的注册信息加入到注册表中。
(1).Client注册
Client 启动后,也会通过RPC在 ROS Master 中注册自身信息,包含需要请求的服务的名称。ROS Master 会将节点的注册信息加入到注册表中。
(2).ROS Master实现信息匹配
ROS Master 会根据注册表中的信息匹配Server和 Client,并通过 RPC 向 Client 发送 Server 的 TCP 地址信息。
(3).Client发送请求
Client 根据步骤2 响应的信息,使用 TCP 与 Server 建立网络连接,并发送请求数据。
(4).Server发送响应
Server 接收、解析请求的数据,并产生响应结果返回给 Client。
注意:
1.客户端请求被处理时,需要保证服务器已经启动;
2.服务端和客户端都可以存在多个。
2 服务通信自定义srv
需求:
服务通信中,客户端提交两个整数至服务端,服务端求和并响应结果到客户端,请创建服务器与客户端通信的数据载体。
srv = 请求 + 响应
流程:
srv 文件内的可用数据类型与 msg 文件一致,且定义 srv 实现流程与自定义 msg 实现流程类似:
-
按照固定格式创建srv文件
-
编辑配置文件
-
编译生成中间文件
(1)定义srv文件
服务通信中,数据分成两部分,请求与响应,在 srv 文件中请求和响应使用---
分割,具体实现如下:
功能包下新建 srv 目录,添加 xxx.srv 文件,内容:
# 客户端请求时发送的两个数字
int32 num1
int32 num2
---
# 服务器响应发送的数据
int32 sum
(2)编辑配置文件
package.xml中添加编译依赖与执行依赖
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
<!--
exce_depend 以前对应的是 run_depend 现在非法
添加构建依赖 和 执行依赖
-->
Copy
CMakeLists.txt编辑 srv 相关配置
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
# 需要加入 message_generation,必须有 std_msgs
add_service_files(
FILES
Addints.srv
)
generate_messages(
DEPENDENCIES
std_msgs
)
注意: 官网没有在 catkin_package 中配置 message_runtime,经测试配置也可以
(3)编译
编译后的中间文件查看:
C++ 需要调用的中间文件(.../工作空间/devel/include/包名/xxx.h)
Python 需要调用的中间文件(.../工作空间/devel/lib/python2.7/dist-packages/包名/srv)
后续调用相关 srv 时,是从这些中间文件调用的 。
3 服务通信自定义srv调用A(C++)
需求:
编写服务通信,客户端提交两个整数至服务端,服务端求和并响应结果到客户端。
分析:
在模型实现中,ROS master 不需要实现,而连接的建立也已经被封装了,需要关注的关键点有三个:
-
服务端
-
客户端
-
数据
流程:
-
编写服务端实现;
-
编写客户端实现;
-
编辑配置文件;
-
编译并执行。
(0)vscode配置
需要像之前自定义 msg 实现一样配置c_cpp_properies.json 文件,如果以前已经配置且没有变更工作空间,可以忽略,如果需要配置,配置方式与之前相同:
{
"configurations": [
{
"browse": {
"databaseFilename": "",
"limitSymbolsToIncludedHeaders": true
},
"includePath": [
"/home/winter/catkin_wp/devel/include/**",
"/opt/ros/melodic/include/**",
"/home/winter/catkin_wp/src/learning_parameter/include/**",
"/home/winter/catkin_wp/src/learning_service/include/**",
"/home/winter/catkin_wp/src/learning_tf/include/**",
"/home/winter/catkin_wp/src/learning_topic/include/**",
"/usr/include/**",
"/home/winter/demo03_ws/devel/include/**"
],
"name": "ROS",
"intelliSenseMode": "gcc-x64",
"compilerPath": "/usr/bin/gcc",
"cStandard": "gnu17",
"cppStandard":"c++17"
}
],
"version": 4
}
(1)服务端
#include "ros/ros.h"
#include "plumbing_server_client/Addints.h"
/*
服务端实现:解析客户端实现的数据,并运算再产生响应
1 包含头文件
2 初始化ros结点
3 创建结点句柄
4 创建服务对象
5 处理请求并产生响应
6 spin()函数
*/
//回调函数
bool doNums(plumbing_server_client::Addints::Request& request,
plumbing_server_client::Addints::Response& response)
{
//处理请求
int num1 = request.num1;
int num2 = request.num2;
ROS_INFO("服务器收到的请求数据是:num1 = %d,num2 = %d",num1,num2);
//响应请求
int num = num1 + num2;
response.sum = num;
ROS_INFO("求和结果是:sum = %d",num);
return true;
}
int main(int argc, char *argv[])
{
//设置中文
setlocale(LC_ALL,"");
//2 初始化ros结点
ros::init(argc,argv,"Server"); //名称保证唯一
//3 创建结点句柄
ros::NodeHandle nh;
//4 创建服务对象
ros::ServiceServer server = nh.advertiseService("Addints",doNums);
ROS_INFO("服务端启动了");
//5 回调函数
//6 spin函数
ros::spin();
return 0;
}
配置文件
add_dependencies(demo01_server ${PROJECT_NAME}_generate_messages_cpp)
测试
roscore
source ./devel/setup.bash
rosrun plumbing_server_client demo01_server
source ./devel/setup.bash
rosservice call Addints "num1: 20
num2: 10"
sum: 30
(2)客户端
#include "ros/ros.h"
#include "plumbing_server_client/Addints.h"
/*
客户端:提交两个整数,处理响应的结果
1 包含头文件
2 初始化ros结点
3 创建结点句柄
4 创建客户对象
5 提交请求并处理响应
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
// 2 初始化ros结点
ros::init(argc,argv,"Client");
// 3 创建结点句柄
ros::NodeHandle nh;
// 4 创建客户对象
ros::ServiceClient client = nh.serviceClient<plumbing_server_client::Addints>("Addints");
// 5 提交请求并处理响应
plumbing_server_client::Addints ai;
//组织请求
ai.request.num1 = 100;
ai.request.num2 = 200;
//处理响应 客户端访问服务器
bool flag = client.call(ai);
if(flag==true)
{
ROS_INFO("响应成功");
//获取结果
ROS_INFO("响应结果是:%d",ai.response.sum);
}
else
{
ROS_INFO("处理失败");
}
return 0;
}
配置文件
roscore
source ./devel/setup.bash
rosrun plumbing_server_client demo01_server
rosrun plumbing_server_client demo02_client
(3)客户端优化
动态提供数据
#include "ros/ros.h"
#include "plumbing_server_client/Addints.h"
/*
客户端:提交两个整数,处理响应的结果
1 包含头文件
2 初始化ros结点
3 创建结点句柄
4 创建客户对象
5 提交请求并处理响应
实现参数的动态提交:
1 格式 rosrun 包名 结点名 参数1 参数2
2 节点执行时要获取命令中的参数,并组织进request 使用argc argv
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
//优化实现,获取命令中的参数
/*
iargc = 3
argv[0] 是文件名
argv[1] 是参数1
argv[2] 是参数2
*/
if(argc !=3)
{
ROS_INFO("提交的参数个数不对");
return 1;
}
// 2 初始化ros结点
ros::init(argc,argv,"Client");
// 3 创建结点句柄
ros::NodeHandle nh;
// 4 创建客户对象
ros::ServiceClient client = nh.serviceClient<plumbing_server_client::Addints>("Addints");
// 5 提交请求并处理响应
plumbing_server_client::Addints ai;
//组织请求
ai.request.num1 =atoi( argv[1]);
ai.request.num2 = atoi(argv[2]);
//处理响应 客户端访问服务器
bool flag = client.call(ai);
if(flag==true)
{
ROS_INFO("响应成功");
//获取结果
ROS_INFO("响应结果是:%d",ai.response.sum);
}
else
{
ROS_INFO("处理失败");
}
return 0;
}
如果先启动客户端,再启动服务端
优化:
在客户端发送请求前添加:
client.waitForExistence();
或:ros::service::waitForService("AddInts");
这是一个阻塞式函数,只有服务启动成功后才会继续执行