服务通信也是ROS中一种极其常用的通信模式,服务通信是基于请求响应模式的,是一种应答机制。也即: 一个节点A向另一个节点B发送请求,B接收处理请求并产生响应结果返回给A。比如如下场景:
- 一个节点需要向相机节点发送拍照请求,相机节点处理请求,并返回处理结果
与上述应用类似的,服务通信更适用于对时时性有要求、具有一定逻辑处理的应用场景。
用于偶然的、对时时性有要求、有一定逻辑处理需求的数据传输场景。
client:客户端
server:服务端
客户端发送请求,服务端请求响应并回应响应结果
注意:
1.客户端请求被处理时,需要保证服务器已经启动;
2.服务端和客户端都可以存在多个。
需求:
服务通信中,客户端提交两个整数至服务端,服务端求和并响应结果到客户端,请创建服务器与客户端通信的数据载体。
流程:
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.编译
编译后的中间文件查看:
C++ 需要调用的中间文件(.../工作空间/devel/include/包名/xxx.h)
Python 需要调用的中间文件(.../工作空间/devel/lib/python3/dist-packages/包名/srv)
后续调用相关 srv 时,是从这些中间文件调用的
2、服务通信自定义srv调用A(C++)
流程:
- 编写服务端实现;
- 编写客户端实现;
- 编辑配置文件;
- 编译并执行
0.vscode配置
需要像之前自定义 msg 实现一样配置c_cpp_properies.json 文件,如果以前已经配置且没有变更工作空间,可以忽略,如果需要配置,配置方式与之前相同:
{
"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
}
服务端:
/*
需求:
编写两个节点实现服务通信,客户端节点需要提交两个整数到服务器
服务器需要解析客户端提交的数据,相加后,将结果响应回客户端,
客户端再解析
服务器实现:
1.包含头文件
2.初始化 ROS 节点
3.创建 ROS 句柄
4.创建 服务 对象
5.回调函数处理请求并产生响应
6.由于请求有多个,需要调用 ros::spin()
*/
#include "ros/ros.h"
#include "plumbing_server_client/AddInts.h"
/*
服务端实现:解析客户端提交提交的数据,并运算再产生响应
1.包含头文件
2.初始化ROS节点;
3.创建节点句柄;
4.创建一个服务对象;
5.处理请求并相应
6.spin()
*/
// bool 返回值由于标志是否处理成功
//当前功能包下面的
bool doNums(plumbing_server_client::AddInts::Request& request,
plumbing_server_client::AddInts::Response& response)
{//当把请求和相应以参数的方式传进来以后就可以处理请求了,处理就是从请求里面把两个数字解析出来
//接下来还有组织响应,组织响应就是把解析出来的数字相加,求出和放进response中
//1.处理请求
int num1 = request.num1;
int num2 = request.num2;
ROS_INFO("服务器接收到的请求数据为:num1 = %d, num2 = %d",num1, num2);
//2.组织响应
int sum = num1+num2;
//逻辑处理
//if (num1 < 0 || num2 < 0)
// {
// ROS_ERROR("提交的数据异常:数据不可以为负数");
// return false;
//}
//如果没有异常,那么相加并将结果赋值给 resp
response.sum = num1 + num2;//求得和放进response
ROS_INFO("求和结果:sum = %d", sum);
return true;
}//在这个回调函数中你得有请求对象和响应对象。
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");//使用中文解析乱码问题
// 2.初始化 ROS 节点
ros::init(argc,argv,"heiShui");//节点名称唯一
// 3.创建 ROS 句柄
ros::NodeHandle nh;
// 4.创建 服务 对象demo01_server
ros::ServiceServer server = nh.advertiseService("AddInts",doNums);//回调函数返回的是布尔类型。第一个参数是话题,第二个参数是回调函数,这个回调函数就相当于是处理请求的,处理请求在这里就有被封装好的对象。
ROS_INFO("服务已经启动....");
// 5.回调函数处理请求并产生响应
// 6.由于请求有多个,需要调用 ros::spin()
ros::spin();
return 0;
}
客户端:
// 1.包含头文件
#include "ros/ros.h"
#include "plumbing_server_client/AddInts.h"
/*
需求:
编写两个节点实现服务通信,客户端节点需要提交两个整数到服务器
服务器需要解析客户端提交的数据,相加后,将结果响应回客户端,
客户端再解析
服务器实现:
1.包含头文件
2.初始化 ROS 节点
3.创建 ROS 句柄
4.创建 客户端 对象
5.请求服务,接收响应
实现参数的动态提交
1.格式:rosrun 包名 节点名称 12 34
2.这个程序进行的时候我们应该是获取到这个两个参数再加到我们的ai的request对象。
2.1节点执行时,需要获取命令中的参数,并组织进request
2.2怎么获取命令中的参数,这里我们可以借助argc和argv
问题:
如果先启动客户端,那么会请求异常
需求:
如果先启动客户端,不要直接抛出异常,而是挂起,等待服务器启动后,再正常请求
解决:
在ROS中内置了相关,这些函数可以让客户端启动后挂起,等待服务器启动
这类函数有两个。
*/
int main(int argc, char *argv[])
{
//优化实现,获取命令中的参数,如果执行rosrun 包名 节点名称 12 34这个命令的话后面跟了两个数字,传进来以后,这个main函数的argc是3吧,然后这个argv他是一个字符串数组,这个数组应该有什么,第一是文件名第二个是参数1,第三个是参数2.
setlocale(LC_ALL,"");
// 调用时动态传值,如果通过 launch 的 args 传参,需要传递的参数个数 +3
if (argc != 3)
if (argc != 5)//launch 传参(0-文件路径 1传入的参数 2传入的参数 3节点名称 4日志路径)
{
ROS_ERROR("请提交两个整数");
return 1;
}
// 2.初始化 ROS 节点
ros::init(argc,argv,"daBao");
// 3.创建 ROS 句柄
ros::NodeHandle nh;
// 4.创建 客户端 对象
ros::ServiceClient client = nh.serviceClient<plumbing_server_client::AddInts>("AddInts");
//等待服务启动成功,
//方式1
ros::service::waitForService("AddInts");
//方式2
// client.waitForExistence();
// 5.组织请求并处理响应
plumbing_server_client::AddInts ai;//不管是请求还是响应,其实在addints里面已经封装好了,所以第一步要创建一个addints的对象
//5.1组织请求
ai.request.num1 = atoi(argv[1]);//c从argv中解析现在还是字符串型的,如果把他变成整型值可以调用atoi
ai.request.num2 = atoi(argv[2]);
//5.2处理响应
//调用判断服务器状态的函数,调用的时机是客户端对象创建完毕之后,然后在发送请求之前。
//函数1
//client.waitForExistence();
//函数2 不过这个函数得
//传参 传的参数是被等待的那个服务 被等待的服务是AddInts
//ros::service::waitForService("AddInts");
//处理响应首先你得有响应,想有响应的话你得让客户端去访问服务器,只有他访问服务器只有才能把这个响应拿到。
//client.call(ai)//相当于我客户端访问了服务器并且把这个ai对象提交了,ai对象里面有request,request里面有num1和num2
//返回值是一个布尔类型的,你提交完以后是要有结果的,然后服务器会返回结果,这个结果用布尔接受一个,如果是true的话正常处理,false的话就是处理失败了。
//另外,他响应回来的结果就是那个sum会继续封装在这个ai对象,在这ai对象中除了有request还有response他会把那个结果封装在response,接下来我们就可以通过ai的response来获取数据了。
//客户端访问服务器:client.call(ai),客户端访问服务器并且把ai对象提交了。服务器会返回结果
// 6.发送请求,返回 bool 值,标记是否成功
bool flag = client.call(ai);
// 7.处理响应
if (flag)
{
ROS_INFO("响应成功");
//获取结果
ROS_INFO("请求正常处理,响应结果:%d",ai.response.sum);
}
else
{
ROS_ERROR("请求处理失败....");
return 1;
}
return 0;
}
3.配置 CMakeLists.txt
add_executable(AddInts_Server src/AddInts_Server.cpp)
add_executable(AddInts_Client src/AddInts_Client.cpp)
add_dependencies(AddInts_Server ${PROJECT_NAME}_gencpp)
add_dependencies(AddInts_Client ${PROJECT_NAME}_gencpp)
target_link_libraries(AddInts_Server
${catkin_LIBRARIES}
)
target_link_libraries(AddInts_Client
${catkin_LIBRARIES}
)
4.执行
流程:
-
需要先启动服务:
rosrun 包名 服务
-
然后再调用客户端 :
rosrun 包名 客户端 参数1 参数2
python
流程:
- 编写服务端实现;
- 编写客户端实现;
- 为python文件添加可执行权限;
- 编辑配置文件;
- 编译并执行。
0.vscode配置
需要像之前自定义 msg 实现一样配置settings.json 文件,如果以前已经配置且没有变更工作空间,可以忽略,如果需要配置,配置方式与之前相同:
{
"python.autoComplete.extraPaths": [
"/opt/ros/noetic/lib/python3/dist-packages",
]
}
Copy
1.服务端
#! /usr/bin/env python
"""
需求:
编写两个节点实现服务通信,客户端节点需要提交两个整数到服务器
服务器需要解析客户端提交的数据,相加后,将结果响应回客户端,
客户端再解析
服务器端实现:
1.导包
2.初始化 ROS 节点
3.创建服务对象
4.回调函数处理请求并产生响应
5.spin 函数
"""
# 1.导包
import rospy
from demo03_server_client.srv import AddInts,AddIntsRequest,AddIntsResponse
# 回调函数的参数是请求对象,返回值是响应对象
def doReq(req):
# 解析提交的数据
sum = req.num1 + req.num2
rospy.loginfo("提交的数据:num1 = %d, num2 = %d, sum = %d",req.num1, req.num2, sum)
# 创建响应对象,赋值并返回
# resp = AddIntsResponse()
# resp.sum = sum
resp = AddIntsResponse(sum)
return resp
if __name__ == "__main__":
# 2.初始化 ROS 节点
rospy.init_node("addints_server_p")
# 3.创建服务对象
server = rospy.Service("AddInts",AddInts,doReq)
# 4.回调函数处理请求并产生响应
# 5.spin 函数
rospy.spin()
Copy
2.客户端
#! /usr/bin/env python
"""
需求:
编写两个节点实现服务通信,客户端节点需要提交两个整数到服务器
服务器需要解析客户端提交的数据,相加后,将结果响应回客户端,
客户端再解析
客户端实现:
1.导包
2.初始化 ROS 节点
3.创建请求对象
4.发送请求
5.接收并处理响应
优化:
加入数据的动态获取
"""
#1.导包
import rospy
from demo03_server_client.srv import *
import sys
if __name__ == "__main__":
#优化实现
if len(sys.argv) != 3:
rospy.logerr("请正确提交参数")
sys.exit(1)
# 2.初始化 ROS 节点
rospy.init_node("AddInts_Client_p")
# 3.创建请求对象
client = rospy.ServiceProxy("AddInts",AddInts)
# 请求前,等待服务已经就绪
# 方式1:
# rospy.wait_for_service("AddInts")
# 方式2
client.wait_for_service()
# 4.发送请求,接收并处理响应
# 方式1
# resp = client(3,4)
# 方式2
# resp = client(AddIntsRequest(1,5))
# 方式3
req = AddIntsRequest()
# req.num1 = 100
# req.num2 = 200
#优化
req.num1 = int(sys.argv[1])
req.num2 = int(sys.argv[2])
resp = client.call(req)
rospy.loginfo("响应结果:%d",resp.sum)
Copy
3.设置权限
终端下进入 scripts 执行:chmod +x *.py
4.配置 CMakeLists.txt
CMakeLists.txt
catkin_install_python(PROGRAMS
scripts/AddInts_Server_p.py
scripts/AddInts_Client_p.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
Copy
5.执行
流程:
-
需要先启动服务:
rosrun 包名 服务
-
然后再调用客户端 :
rosrun 包名 客户端 参数1 参数2
结果:
会根据提交的数据响应相加后的结果。