服务通信
服务通信也是ROS中一种极其常用的通信模式,服务通信是基于请求响应模式的,是一种应答机制。也即: 一个节点A向另一个节点B发送请求,B接收处理请求并产生响应结果返回给A。比如如下场景:
机器人巡逻过程中,控制系统分析传感器数据发现可疑物体或人... 此时需要拍摄照片并留存。
在上述场景中,就使用到了服务通信。
- 一个节点需要向相机节点发送拍照请求,相机节点处理请求,并返回处理结果
与上述应用类似的,服务通信更适用于对时时性有要求、具有一定逻辑处理的应用场景。
理论模型
服务通信较之于话题通信更简单些,理论模型如下图所示,该模型中涉及到三个角色:
- 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.服务端和客户端都可以存在多个。
在模型实现中,ROS master 不需要实现,而连接的建立也已经被封装了,需要关注的关键点有三个:
- 服务端
- 客户端
- 数据
流程:
- 编写服务端实现;
- 编写客户端实现;
- 为python文件添加可执行权限;
- 执行。
自定义srv
需求:
服务通信中,客户端提交两个整数至服务端,服务端求和并响应结果到客户端,请创建服务器与客户端通信的数据载体。
流程:
srv 文件内的可用数据类型与 msg 文件一致,且定义 srv 实现流程与自定义 msg 实现流程类似:
- 按照固定格式创建srv文件
- 编辑配置文件
- 编译生成中间文件
定义srv文件
服务通信中,数据分成两部分,请求与响应,在 srv 文件中请求和响应使用---
分割,具体实现如下:
功能包下新建 srv 目录,添加 AddInts.srv
文件,内容:
| int32 a
int32 b
---
int32 sum
|
说明:请求中有两个整数 a
和 b
,响应中返回 sum
。

编辑CMakeLists.txt
编辑功能包下的 CMakeLists.txt:
| ## 查找依赖的 catkin 包
find_package(catkin REQUIRED COMPONENTS
rospy # ROS Python 支持库
std_msgs # 标准消息类型
message_generation # 生成自定义消息/服务所需的模块
# 需要加入 message_generation,必须有 std_msgs
)
## 添加服务文件(.srv)
add_service_files(
FILES
AddInts.srv # 你定义的服务文件,多个用空格分隔
)
## 根据 .srv/.msg 文件生成代码(Python/C++ 支持等)
generate_messages(
DEPENDENCIES
std_msgs # 如果服务使用了 std_msgs 中的类型,则需要依赖它
)
## 声明 catkin 包
catkin_package(
CATKIN_DEPENDS message_runtime std_msgs # 运行时依赖消息相关的功能包
)
|
注意: 官网没有在 catkin_package 中配置 message_runtime,经测试配置也可以
编辑package.xml
编辑功能包下的 package.xml:
| <!-- 构建所需的依赖 -->
<buildtool_depend>catkin</buildtool_depend>
<!-- 构建阶段需要的功能包 -->
<build_depend>message_generation</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>rospy</build_depend>
<!-- 安装/运行时需要的功能包 -->
<exec_depend>message_runtime</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>rospy</exec_depend>
|
编译
回到工作空间根目录并编译:
编译成功后,Python 需要调用的中间文件(工作空间/devel/lib/python3/dist-packages/包名/srv)

后续在 Python中调用相关 srv时,就是从这些中间文件调用的:
| from service_ros.srv import AddInts,AddIntsRequest,AddIntsResponse
|
服务端
add_server.py
:
| #!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy
from service_ros.srv import AddInts, AddIntsResponse # 导入自定义服务类型(请求和响应)
# 定义服务处理函数,参数为请求内容(req)
def do_req(req):
# 日志打印客户端请求的数据
rospy.loginfo("请求数据: a = %d, b = %d", req.a, req.b)
# 处理逻辑:将两个数相加,并返回响应对象
sum= req.a + req.b
return AddIntsResponse(sum) # 返回响应,字段名必须和 .srv 文件一致
if __name__ == "__main__":
rospy.init_node("add_server") # 初始化节点
rospy.loginfo("服务端已启动...")
# 定义服务名、服务类型、回调函数
server = rospy.Service("add_two_ints", AddInts, do_req)
# 等待请求(循环等待)
rospy.spin()
|
客服端
add_client.py
:
| #!/usr/bin/env python
# -*- coding: utf-8 -*-
# 上面两行是指定解释器和编码格式(Python 3 默认 UTF-8,此处为兼容性保留)
import rospy # 导入 ROS Python 接口库
import sys # 导入 sys 模块,用于接收命令行参数
from service_ros.srv import AddInts # 导入服务类型 AddInts(由 .srv 文件自动生成)
if __name__ == "__main__":
rospy.init_node("add_client") # 初始化 ROS 节点,名称为 add_client
# 判断命令行参数是否正确(包括脚本名总共应为3个参数)
if len(sys.argv) != 3:
rospy.logerr("请正确提交两个参数") # 提示正确用法
sys.exit(1) # 参数错误则退出程序
# 读取命令行参数并转换为整数
a = int(sys.argv[1])
b = int(sys.argv[2])
# 等待服务端节点启动并提供名为 add_two_ints 的服务
# rospy.wait_for_service("add_two_ints")
try:
# 创建服务代理对象,指定服务名和类型
client = rospy.ServiceProxy("add_two_ints", AddInts)
# 等待服务端节点启动并提供名为 add_two_ints 的服务
client.wait_for_service()
# 调用服务,将 a 和 b 作为请求参数传入,获取返回结果
response = client(a, b)
# 输出结果日志:显示两个数相加的结果
rospy.loginfo("请求结果: %d + %d = %d", a, b, response.sum)
except rospy.ServiceException as e:
# 如果服务调用失败,打印错误日志
rospy.logerr("服务调用失败: %s" % e)
|
添加可执行权限
为python文件添加可执行权限:
运行
终端1:
终端2:
| rosrun service_ros add_server.py
|

终端3:
| rosrun service_ros add_client.py 10 20
|

