服务通信
概述
服务通信也是ROS中一种极其常用的通信模式,服务通信是基于请求响应模式的,是一种应答机制。也即: 一个节点A向另一个节点B发送请求,B接收处理请求并产生响应结果返回给A。比如如下场景:
机器人巡逻过程中,控制系统分析传感器数据发现可疑物体或人… 此时需要拍摄照片并留存。
在上述场景中,就使用到了服务通信。
- 一个节点需要向相机节点发送拍照请求,相机节点处理请求,并返回处理结果
与上述应用类似的,服务通信更适用于对实时性有要求、具有一定逻辑处理的应用场景。
理论模型
角色
- master -> 管理者
- server -> 服务端
- client -> 客户端
流程
master根据话题实现server与client的连接
0、server在master中注册信息
1、client在master中注册话题
2、master将ROSRPC返回给client
3、client向server发起请求
4、server响应数据
注意
- 客户端发起请求时,保证服务端已经启动
- 客户端与服务端不唯一
- 需要注册话题
实现
编写服务通信,客户端提交两个整数至服务端,服务端求和并响应结果到客户端。请创建服务器与客户端通信的数据载体
自定义服务srv
在之前的话题通信中,发布方作为消息的发送者,订阅方作为消息的接收者,也就是说发布方发布什么样的消息,订阅方就接收到什么样的消息;但在服务通信中,客户端向服务端提交的数据经服务端进行计算后返回,因此服务通信中的消息结构就必须有请求和响应两部分构成。srv文件用于定义服务通信的消息请求和响应,用---
进行分割.
流程
创建srv文件
在功能包下创建srv文件夹并创建.srv文件。
1 2 3 4
| int32 num1 int32 num2 --- int32 sum
|
编辑配置文件
package.xml
1 2
| <build_depend>message_generation</build_depend> <exec_depend>message_runtime</exec_depend>
|
CMakeLists.txt
1 2 3 4 5 6
| find_package(catkin REQUIRED COMPONENTS roscpp rospy std_msgs message_generation )
|
1 2 3 4
| add_service_files( FILES AddInt.srv )
|
1 2 3 4
| generate_messages( DEPENDENCIES std_msgs )
|
编译后就可以在服务通信中使用该消息结构。
C++实现
在模型实现中,大部分底层的逻辑已经封装在ROS中,在开发过程中我们只需要关注一下三方面:
- 服务端
- 客户端
- 数据
流程:
服务端实现;
客户端实现;
编辑配置文件;
编译执行。
vscode配置
需要像之前自定义 msg 实现一样配置c_cpp_properies.json 文件,如果以前已经配置且没有变更工作空间,可以忽略,如果需要配置,配置方式与之前相同:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22
| { "configurations": [ { "browse": { "databaseFilename": "", "limitSymbolsToIncludedHeaders": true }, "includePath": [ "/opt/ros/noetic/include/**", "/usr/include/**", "/xxx/yyy工作空间/devel/include/**" ], "name": "ROS", "intelliSenseMode": "gcc-x64", "compilerPath": "/usr/bin/gcc", "cStandard": "c11", "cppStandard": "c++17" } ], "version": 4 } Copy
|
服务端
- 包含头文件
- 初始化ROS节点
- 创建节点句柄
- 创建服务对象
- 处理请求产生响应
- spin()
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32
| # include "ros/ros.h" # include "plumbing_server_client/AddInt.h"
bool handleRequest(plumbing_server_client::AddInt::Request &request, plumbing_server_client::AddInt::Response &response){
int num1 = request.num1; int num2 = request.num2; ROS_INFO("收到的请求数据:num1=%d,num2=%d",num1,num2); int sum = num1 + num2; response.sum = sum; ROS_INFO("结果:%d",sum); return true; }
int main(int argc, char *argv[]){ setlocale(LC_ALL,"");
ros::init(argc, argv, "sum");
ros::NodeHandle nh;
ros::ServiceServer server = nh.advertiseService("addInts",handleRequest);
ROS_INFO("服务端启动");
ros::spin();
return 0; }
|
客户端
- 包含头文件
- 初始化ROS节点
- 创建节点句柄
- 创建请求对象
- 提交请求处理响应
- spin()
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36
| #include "ros/ros.h" #include "plumbing_server_client/AddInt.h"
int main(int argc, char *argv[]){
setlocale(LC_ALL, "");
if(argc != 3){ ROS_INFO("提交参数个数有误,需要:3 个,提交:%d 个",argc); return 1; }
ros::init(argc, argv, "client_1");
ros::NodeHandle nh;
ros::ServiceClient client = nh.serviceClient<plumbing_server_client::AddInt>("addInts"); plumbing_server_client::AddInt ai;
ai.request.num1 = atoi(argv[1]);
ai.request.num2 = atoi(argv[2]);
bool flag = client.call(ai);
if(flag){ ROS_INFO("请求成功,返回结果:%d",ai.response.sum); } else{ ROS_INFO("请求失败"); }
return 0; }
|
配置 CMakeLists.txt
1 2 3 4 5 6 7 8 9 10 11 12 13 14
| add_executable(server src/server.cpp) add_executable(client src/client.cpp)
add_dependencies(server ${PROJECT_NAME}_gencpp) add_dependencies(client ${PROJECT_NAME}_gencpp)
target_link_libraries(server ${catkin_LIBRARIES} ) target_link_libraries(client ${catkin_LIBRARIES} )
|
执行
流程:
结果:
会根据提交的数据响应相加后的结果。
注意
如果调换启动顺序,先启动客户端,由于服务端未在ROS注册,客户端找不到server的话题,就无法建立起连接。但在实际应用过程中可能会存在客户端先启动的情况。
ROS提供了c++函数接口用于在服务端未启动的情况下挂起客户端,当服务端启动后再去进行请求。
1 2
| client.waitForExistenZce(); // ros::ServiceClient client ros::service::waitForService(server_topic);
|
Python实现
vscode配置
需要像之前自定义 msg 实现一样配置settings.json 文件,如果以前已经配置且没有变更工作空间,可以忽略,如果需要配置,配置方式与之前相同:
1 2 3 4 5 6
| { "python.autoComplete.extraPaths": [ "/opt/ros/noetic/lib/python3/dist-packages", ] }
|
服务端
- 导包
- 初始化ROS节点
- 创建服务对象
- 处理请求产生响应
- spin()
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30
|
from urllib import response import rospy from plumbing_server_client.srv import *
def callback(request):
num1 = request.num1 num2 = request.num2
sum = num1 + num2
res = AddIntResponse()
res.sum = sum
rospy.loginfo("计算结果:{}".format(sum))
return res if __name__ == "__main__": rospy.init_node("server_py")
rospy.loginfo("服务端启动")
server = rospy.Service("addInts", AddInt, callback)
rospy.spin()
|
客户端
- 导包
- 初始化ROS节点
- 创建请求对象
- 提交请求处理响应
- spin()
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23
|
import rospy import sys from plumbing_server_client.srv import *
if __name__ == "__main__":
if len(sys.argv) != 3: rospy.loginfo("提交参数个数有误,需要:3 个,提交:{} 个".format(len(sys.argv))) sys.exit(1)
rospy.init_node("client_py")
client = rospy.ServiceProxy("addInts", AddInt)
num1 = int(sys.argv[1]) num2 = int(sys.argv[2]) res = client.call(num1,num2)
rospy.loginfo("请求数据:num1={},num2={},响应数据:{}".format(num1, num2, res))
|
设置权限
终端下进入 scripts 执行:chmod +x *.py
配置 CMakeLists.txt
CMakeLists.txt
1 2 3 4 5 6
| catkin_install_python(PROGRAMS scripts/server.py scripts/client.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) Copy
|
执行
流程:
- 需要先启动服务:
rosrun 包名 服务
- 然后再调用客户端 :
rosrun 包名 客户端 参数1 参数2
结果:
会根据提交的数据响应相加后的结果。
注意
ROS提供了c++函数接口用于在服务端未启动的情况下挂起客户端,当服务端启动后再去进行请求。
1 2
| client.wait_for_service() rospy.wait_for_service(server_topic)
|