目录
服务通信是ROS中一种极其常用的通信模式,服务通信是基于请求响应模式的,是一种应答机制。即: 一个节点A向另一个节点B发送请求,B接收处理请求并产生响应结果返回给A。服务通信适用于对实时性有要求、具有一定逻辑处理的应用场景。
服务通信的理论模型
服务通信自定义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 现在非法
-->
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
)
3.编译
编译成功后会产生相应的中间文件
服务通信自定义srv调用B(Python)
要求:编写服务通信,客户端提交两个整数至服务端,服务端求和并响应结果到客户端。
分析:
在模型实现中,ROS master 不需要实现,而连接的建立也已经被封装了,需要关注的关键点有三个:
- 服务端
- 客户端
- 数据
流程:
- 编写服务端实现;
- 编写客户端实现;
- 为python文件添加可执行权限;
- 编辑配置文件;
- 编译并执行。
vscode配置:
需要像之前自定义 msg 实现一样配置settings.json 文件,如果以前已经配置且没有变更工作空间,可以忽略,如果需要配置,配置方式与之前相同:
{
"python.autoComplete.extraPaths": [
"/opt/ros/noetic/lib/python3/dist-packages",
]
}
服务端实现:
#! /usr/bin/env python
import rospy
from plumbing_server_client.srv import *
'''
服务端:解析客户端请求,产生响应
1.导包
2.初始化ROS节点
3.创建服务端对象
4.编写处理逻辑(回调函数)
5.spin()
'''
#参数:封装了请求数据
#返回值:相应数据
def doNum(request):
#1.解析提交的两个整数
num1 = request.num1
num2 = request.num2
#2.求和
sum = num1 + num2
#将结果封装进响应
response = AddIntsResponse()
response.sum = sum
rospy.loginfo("服务器解析的数据num1 = %d, num2 = %d,响应的结果:sum = %d",num1,num2,sum)
return response
if __name__ == "__main__":
# 2.初始化ROS节点
rospy.init_node("heiShui")
# 3.创建服务端对象
sever = rospy.Service("addInts",AddInts,doNum)
rospy.loginfo("服务器已经启动")
# 4.编写处理逻辑(回调函数)
# 5.spin()
rospy.spin()
客户端
#! /usr/bin/env python
import rospy
from plumbing_server_client.srv import *
import sys
'''
客户端:组织并提交请求,处理服务端响应
1.导包
2.初始化ROS节点
3.创建客户端对象
4.组织请求数据,并发送请求
5.处理响应
优化实现:
可以在执行节点时,动态传入参数
'''
if __name__ == "__main__":
#判断参数长度
if len(sys.argv) != 3:
rospy.logerr("传入的参数个数不对")
sys.exit(1)
# 2.初始化ROS节点
rospy.init_node("erHei")
# 3.创建客户端对象
client = rospy.ServiceProxy("addInts",AddInts)
# 4.组织请求数据,并发送请求
# 解析传入的参数
num1 = int(sys.argv[1])
num2 = int(sys.argv[2])
response = client.call(num1,num2)
# 5.处理响应
rospy.loginfo("响应的结果为:%d",response.sum)
执行的结果: