服务通信涉及到三个角色:
ROS master(管理者)、Server(服务端)、Client(客户端)
ROS Master 负责保管 Server 和 Client 注册的信息,并匹配话题相同的 Server 与 Client ,帮助 Server 与 Client 建立连接,连接建立后,Client 发送请求信息,Server 返回响应信息
- 实现需求:服务通信中,客户端提交两个整数至服务端,服务端求和并响应结果到客户端
srv 文件内的可用数据类型与 msg 文件一致,且定义 srv 实现流程与自定义 msg 实现流程类似:
- 定义srv文件-----功能包plumbing_server_client下新建 srv 目录,添加 Addints.srv 文件
在 srv 文件中请求和响应使用-------分割
# 客户端请求时发送的两个数字
int32 num1
int32 num2
----------
# 服务器响应发送的数据
int32 sum
- 编辑配置文件(和msg配置一样,请参考上一节),编译会生成相关文件,即Addints.h/Addints.py
- 编写服务通信
3.0 Vscode配置
像之前自定义 msg 实现一样配置c_cpp_properies.json /settings.json 文件,如果以前已经配置且没有变更工作空间,可以忽略,如果需要配置, 配置Addints.h/Addints.py的工作路径;
3.1 C++实现
(1)客户端实现:
#include "ros/ros.h"
#include "plumbing_server_client/Addints.h"
/*
1.包含头文件
2.初始化ROS节点
3.创建节点句柄
4.创建一个客户端对象
5.提交请求并处理响应
实现参数的动态提交:
1.格式:rosrun xxxx xxxx 12 43
2.节点执行时,需要获取命令中的参数,并组织进 request
*/
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
//优化实现,获取命令中参数
if(argc !=3){
ROS_INFO("提交的参数个数不对。");
return 1;
}
//2.初始化ROS节点
ros::init(argc,argv,"dabao"); //节点名称唯一
//3.创建节点句柄
ros::NodeHandle nh;
//4.创建一个客户端对象
ros::ServiceClient client = nh.serviceClient<plumbing_server_client::Addints>("addints");
//如果先启动客户端,那么会导致运行失败
//优化,本质上一个阻塞式函数,只有服务启动成功后才会继续执行
//方案1
//client.waitForExistence();
//方案2
ros::service::waitForService("AddInts");
//5.提交请求并处理响应
plumbing_server_client::Addints ai;
//5-1组织请求
ai.request.num1 = atoi(argv[1]);
ai.request.num2 = atoi(argv[2]);
//5-2处理响应
bool flag = client.call(ai);
if (flag)
{
ROS_INFO("响应成功!");
//获取结果
ROS_INFO("响应结果 = %d",ai.response.sum);
} else
{
ROS_INFO("处理失败......");
}
return 0;
}
(2)服务端实现:
#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 &resonse){
//1.处理请求
int num1 = request.num1;
int num2 = request.num2;
ROS_INFO("收到的请求数据:num1 = %d, num2 = %d",num1,num2);
//2.组织响应
int sum = num1 +num2;
resonse.sum = sum;
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::NodeHandle nh;
//4.创建一个服务对象
ros::ServiceServer server = nh.advertiseService("addints",doNums);
ROS_INFO("服务器端启动");
//5.处理请求并产生响应
//6.spin()
ros::spin();
return 0;
(3)配置CMakeList.txt文件(略),编译执行
-3.2 Python实现
(1)客户端实现
#! /usr/bin/env python
# -*- coding: UTF-8 -*-
import rospy
from plumbing_server_client.srv import *
'''
客户端:组织并提交请求,处理服务端响应
1.导包
2.初始化ROS节点
3.创建客户端对象
4.组织请求数据,并发送请求
5.处理响应
'''
if __name__ == "__main__":
#初始化ROS节点
rospy.init_node("erhei")
#创建客户端对象
client = rospy.ServiceProxy("addints",Addints)
# 请求前,等待服务已经就绪
# 方式1:
# rospy.wait_for_service("AddInts")
# 方式2
client.wait_for_service()
response = client.call(12,43)
rospy.loginfo("Response data:%d",response.sum)
(2)服务端实现
#! /usr/bin/env python
# -*- coding: UTF-8 -*-
import rospy
from plumbing_server_client.srv import *
#回调函数处理请求并产生响应
# 回调函数的参数是请求对象,返回值是响应对象
def doNum(request):
#解析提交的数据
num1 = request.num1
num2 = request.num2
sum = num1 +num2
#创建响应对象并赋值返回
response = AddintsResponse()
response.sum = sum
rospy.loginfo("提交的数据:num1=%d, num2=%d,返回的结果:sum = %d",num1,num2,sum)
if __name__ == "__main__":
rospy.init_node("heishui")
#创建服务对象
server = rospy.Service("addints",Addints,doNum)
rospy.loginfo("The server start.")
#spin()函数
rospy.spin()
(3)添加可执行权限(略),编译并执行