ROS服务通信具体实现流程
demo:实现两个整型数相加求和,客户端发送两个整型数,服务端对其求和。
服务通信也需要自定义服务数据类型,即自定义srv文件,该过程和自定义msg文件非常类似。主要实现流程分为以下三步:①按照固定格式创建srv文件②编辑相关配置文件③编译生成中间文件
开始之前首先要在工作空间中的src文件夹中新建一个功能包,可以用catkin_create_pkg 功能包名 依赖,建立一个新的功能包。这里我命名为server_client。
(1)按照固定格式创建srv文件
在新建功能包server_client中新建一个文件夹命名为srv,在srv文件中新建文件命名为AddInts.srv用于存放我们的消息载体。
srv文件中存放的变量结构体按照请求和相应分为两部分,用—隔开
(2)编辑配置文件package.xml和CMakelist.txt
①首先编辑package.xml文件
②编辑CMakelist.txt文件
注意下面这个不同于话题通信,需要配置srv相关部分,将注释放开,并把我们新建的AddInts.srv更换到文件下面
将generate_messages注释放开,因为这里虽然我们的通信数据格式是自定义的,但是它的产生依然依赖于标准包std_msgs
放开注释catkin_packages,类似话题通信,这里也是为了满足包之间的依赖关系。
到这里呢,我们的配置就终于完成啦~接下来进入编译环节
(3)编译生成中间文件
ctrl+shift+B
可以看到我们的编译并未抛出异常
如果这里报错“Invoking “cmake”failed,很有可能是包名写错啦,回去检查一下重新编译就好啦
(3)编译生成中间文件
可以看到我们已经在开发空间devel中产生了一些后续被调用到的文件。这样我们的数据结构文件就配置好啦~可以进行下一步的开发咯
(4)自定义srv文件的调用
模型实现中:rosmaster可以通过roscore启动,建立连接的具体过程已被官方封装好
我们需要做的工作主要分为以下三个部分:①服务端程序编写②客户端程序编写③数据
VScode配置
使用自定义srv文件时,需要对VScode进行一些配置,这样可以使VS提供对应的语法高亮,便于我们编程,也能防止VScode误抛异常。不配置也不影响使用。
服务端代码实现
定位到功能包,新建文件夹scripts,新建文件server.py
创建服务对象用到的函数rospy.Service(”话题名“,数据类型,回调函数),话题名自定义(服务端和客户端需要保持一致),数据类型取决于srv文件的自定义名称,回调函数自己编写和spin()成对出现。
#! /usr/bin/env python
import rospy
from server_client.srv import AddInts,AddIntsRequest,AddIntsResponse
#这里可以import*,不用写清楚具体的类和对象,这样会把该文件的所有对象都导入,但是要注意文件大的时候这样处理会变慢很多
"""
服务端:解析客户需求,产生响应
1、导包
2、初始化ros节点
3、创建服务端对象
4、数据处理逻辑(回调函数)
5、spin()
"""
#参数:封装了请求数据
#返回值:响应数据
def doAdd(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)
return response
if __name__=="__main__":
#初始化ROS节点
rospy.init_node("fuwu")
#创建服务对象,注意函数大小写,数据类型取决于srv文件的文件名
server = rospy.Service("addints",AddInts,doAdd)
rospy.loginfo("服务器已经启动了")
rospy.spin()
配置CMakelist.txt
改变文件可执行权限,source刷新环境变量,rosrun运行,可以看到服务器启动了
客户端还未编写,我们这里可以用命令模拟客户端来测试服务端的功能,call后面要加自定义的建立通信链接的话题名,之后可以tab键自动补齐数据结构类型,手动修改数据并执行即可测试。
rosservice call addints "num1:1,num2:2"
客户端代码实现
定位到功能包,新建文件夹scripts,新建文件client.py
创建客户对象用到的函数rospy.ServiceProxy(”话题名“,消息数据类型),话题名和服务端保持一致,数据类型同服务端,取决于srv文件,这里是AddInts。
请求数据并发送请求:client.call(num1,num2)
#! /usr/lib/env python
import rospy
from server_client.srv import AddInts,AddIntsRequest,AddIntsResponse
"""
1、导包
2、初始化ros节点
3、创建客户端对象
4、组织请求数据,并发送请求
5、处理响应
"""
if __name__=="__main__":
rospy.init_node("kehu")
#创建客户端对象
client = rospy.ServiceProxy("addints",AddInts)
#组织请求数据,并发送请求
response = client.call(12,23)
#处理响应,这里直接打印一下
rospy.loginfo("响应求和之后的数据是%d",response.sum)
程序执行结果:
优化实现:
(1)可以在执行节点时,动态传入参数
用到模块sys中的argv。这个可以包含节点名称和传入的数据。
(2)解决问题:
当客户端先于服务端启动时,程序会抛出异常,但是ROS节点在启动时是没有先后顺序的,那么在程序执行过程中可能会出现一些问题
解决方案:
当客户端先于服务端启动时,不要抛出异常,而是要挂起等待。等待服务器启动后,再次发送请求
实现代码:
ROS中的内置函数,判断服务器的状态,服务端未启动时客户端挂起。
法一: client.wait_for_service(),不需要传入话题名称,它本身可以查找话题名
法二: rospy.wait_for_service(“话题”)rospy需要传入参数话题名称
#! /usr/lib/env python
import rospy
from server_client.srv import AddInts,AddIntsRequest,AddIntsResponse
import sys
"""
1、导包
2、初始化ros节点
3、创建客户端对象
4、组织请求数据,并发送请求
5、处理响应
问题:
当客户端先于服务端启动时,程序会抛出异常,但是ROS节点在启动时是没有先后顺序的,那么在程序执行过程中可能会出现一些问题
解决方案:
当客户端先于服务端启动时,不要抛出异常,而是要挂起等待。等待服务器启动后,再次发送请求
实现代码:
ROS中的内置函数,判断服务器的状态,服务端未启动时客户端挂起。
法一:client.wait_for_service(),不需要传入话题名称,它本身可以查找话题名
法二:rospy.wait_for_service("话题")rospy需要传入参数话题名称
"""
if __name__=="__main__":
#判断参数长度,由于节点名也算一个参数,argv[0]是节点名,所以这里是3
if len(sys.argv)!=3:
rospy.logerr("传入的参数个数不对")
sys.exit(1)
rospy.init_node("kehu")
#创建客户端对象
client = rospy.ServiceProxy("addints",AddInts)
#组织请求数据,并发送请求,argv[1]这里是字符串类型,需要强行将其转换为int类型
num1 = int(sys.argv[1])
num2 = int(sys.argv[2])
#等待服务器启动
#client.wait_for_service()
#法二
rospy.wait_for_service("addints")
response = client.call(num1,num2)
#处理响应,这里直接打印一下
rospy.loginfo("响应求和之后的数据是%d",response.sum)
从程序执行结果可以看到,可以动态输入num1和num2,crtl C关闭服务端后,先执行客户端,客户端程序不会抛出异常而是会挂起等待,开启服务端后正常响应。