1.基本介绍
服务通信较之于话题通信更简单些,理论模型如下图所示,该模型中涉及到三个角色:
- 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.服务端和客户端都可以存在多个。
2.具体实现
2.1创建srv文件
创建服务通信功能包
注意是右键工作空间下面的src文件夹Create Kitcan Package ,并添加依赖
新建srv文件夹,添加编程文件
服务通信中,数据分成两部分,请求与响应,在 srv 文件中请求和响应使用---
分割,具体实现如下:
# 客户端请求时发送的两个数字
int32 num1
int32 num2
---
# 服务器响应发送的数据
int32 sum
编辑配置文件
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
)
修改完成以后编译
2.2服务通信自定义srv(C++)
2.2.1服务端
VScode配置
找到该文件夹,在终端中打开,pwd,查看路径,复制路径到图片所示文件中
在功能包下的src文件夹里面新建编程文件
编写以下代码
/*
需求:
编写两个节点实现服务通信,客户端节点需要提交两个整数到服务器
服务器需要解析客户端提交的数据,相加后,将结果响应回客户端,
客户端再解析
服务器实现:
1.包含头文件
2.初始化 ROS 节点
3.创建 ROS 句柄
4.创建 服务 对象
5.回调函数处理请求并产生响应
6.由于请求有多个,需要调用 ros::spin()
*/
#include "ros/ros.h"
#include "server_client/AddInts.h"
// bool 返回值由于标志是否处理成功
bool doReq(server_client::AddInts::Request& req,
server_client::AddInts::Response& resp){
int num1 = req.num1;
int num2 = req.num2;
ROS_INFO("服务器接收到的请求数据为:num1 = %d, num2 = %d",num1, num2);
//逻辑处理
if (num1 < 0 || num2 < 0)
{
ROS_ERROR("提交的数据异常:数据不可以为负数");
return false;
}
//如果没有异常,那么相加并将结果赋值给 resp
resp.sum = num1 + num2;
return true;
}
int main(int argc, char *argv[])
{
setlocale(LC_ALL,"");
// 2.初始化 ROS 节点
ros::init(argc,argv,"AddInts_Server");
// 3.创建 ROS 句柄
ros::NodeHandle nh;
// 4.创建 服务 对象
ros::ServiceServer server = nh.advertiseService("AddInts",doReq);
ROS_INFO("服务已经启动....");
// 5.回调函数处理请求并产生响应
// 6.由于请求有多个,需要调用 ros::spin()
ros::spin();
return 0;
}
修改配置文件
add_executable(demo01_server src/demo01_server.cpp)
add_dependencies(demo01_server ${PROJECT_NAME}_gencpp)
target_link_libraries(demo01_server
${catkin_LIBRARIES}
)
运行代码查看效果
使用ros服务器工具进行查验代码
rosservice call AddInts "num1: 5
num2: 10"
2.2.2客户端
新建编程文件如图
输入以下代码
/*
需求:
编写两个节点实现服务通信,客户端节点需要提交两个整数到服务器
服务器需要解析客户端提交的数据,相加后,将结果响应回客户端,
客户端再解析
服务器实现:
1.包含头文件
2.初始化 ROS 节点
3.创建 ROS 句柄
4.创建 客户端 对象
5.请求服务,接收响应
*/
// 1.包含头文件
#include "ros/ros.h"
#include "server_client/AddInts.h"
int main(int argc, char *argv[])
{
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,"AddInts_Client");
// 3.创建 ROS 句柄
ros::NodeHandle nh;
// 4.创建 客户端 对象
ros::ServiceClient client = nh.serviceClient<server_client::AddInts>("AddInts");
//等待服务启动成功
//方式1
ros::service::waitForService("AddInts");
//方式2
// client.waitForExistence();
// 5.组织请求数据
server_client::AddInts ai;
ai.request.num1 = atoi(argv[1]);
ai.request.num2 = atoi(argv[2]);
// 6.发送请求,返回 bool 值,标记是否成功
bool flag = client.call(ai);
// 7.处理响应
if (flag)
{
ROS_INFO("请求正常处理,响应结果:%d",ai.response.sum);
}
else
{
ROS_ERROR("请求处理失败....");
return 1;
}
return 0;
}
修改配置文件
add_executable(demo01_server src/demo01_server.cpp)
add_executable(demo02_client src/demo02_client.cpp)
add_dependencies(demo01_server ${PROJECT_NAME}_gencpp)
add_dependencies(demo02_client ${PROJECT_NAME}_gencpp)
target_link_libraries(demo01_server
${catkin_LIBRARIES}
)
target_link_libraries(demo02_client
${catkin_LIBRARIES}
)
运行查看结果
https://mp.csdn.net/mp_download/manage/download/UpDetailed
2.3服务通信自定义srv(Python)
路径配置
右键文件夹复制路径
/home/xiaoming/demo0/devel/lib/python2.7/dist-packages
2.3.1服务端创建
创建代码文件夹及代码文件
#! /usr/bin/env python
# -*- coding: UTF-8 -*-
"""
需求:
编写两个节点实现服务通信,客户端节点需要提交两个整数到服务器
服务器需要解析客户端提交的数据,相加后,将结果响应回客户端,
客户端再解析
服务器端实现:
1.导包
2.初始化 ROS 节点
3.创建服务对象
4.回调函数处理请求并产生响应
5.spin 函数
"""
# 1.导包
import rospy
from 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)
rospy.loginfo("服务器已经启动了!")
# 4.回调函数处理请求并产生响应
# 5.spin 函数
rospy.spin()
添加可执行文件
编辑可执行文件
catkin_install_python(PROGRAMS
scripts/demo01_server_p.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
运行显示效果
2.3.2客户端创建
创建编程文件并输入代码
#! /usr/bin/env python
# -*- coding: UTF-8 -*-
"""
需求:
编写两个节点实现服务通信,客户端节点需要提交两个整数到服务器
服务器需要解析客户端提交的数据,相加后,将结果响应回客户端,
客户端再解析
客户端实现:
1.导包
2.初始化 ROS 节点
3.创建请求对象
4.发送请求
5.接收并处理响应
优化:
加入数据的动态获取
"""
#1.导包
import rospy
from server_client.srv import AddInts,AddIntsRequest,AddIntsResponse
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)
添加可执行文件
修改可执行文件
catkin_install_python(PROGRAMS
scripts/demo01_server_p.py
scripts/demo02_client_p.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
运行查看效果
https://mp.csdn.net/mp_download/manage/download/UpDetailed