Service通讯和代码练习
- 六、Service通讯
- 6.1 Server端创建
- 6.1.1 创建节点
- 6.1.2 处理请求的逻辑
- 6.1.3 Server端实现
- 6.2 Server端调试
- 6.2.1 rosservice工具(命令行)
- 6.2.2 rqt_service_caller工具(可视化)
- 6.3 Client端创建
- 6.3.1 创建节点
- 6.3.2 调用Service
- 6.3.3 Client端实现
- 6.4 Client端调试
- 6.5 Service命令行工具
- 6.1 Server端创建
- 七、Service通讯练习
六、Service通讯
6.1 Server端创建
安装 pyserial
pip install pyserial
工作空间下创建功能包
cd ros_ws/first_ws/src
catkin_create_pkg hello_service rospy roscpp rosmsg
使用Clion打开目录 hello_service
,在 scripts
目录下新建Python文件 server_node
6.1.1 创建节点
rospy.init_node('server_node')
按 Ctrl + P 第一个参数
serviceName
为服务名称,为一个uri地址 第二个参数service_class
是服务需要的数据类型 第三个参数handle
为服务请求的回调
6.1.2 处理请求的逻辑
def callback(request):
if not isinstance(request, AddTwoIntsRequest): return
a = request.a
b = request.b
# 业务逻辑处理
c = a + b
# 返回相应结果
response = AddTwoIntsResponse()
response.sum = c
return response
回调函数的参数是请求过来的数据 返回值是响应的数据
6.1.3 Server端实现
完整代码如下:
#!/usr/bin/env python
# -*- coding: utf-8 -*-
# @Time : 15/9/20 12:38 AM
# @Author : Chenan_Wang
# @File : server_node.py
# @Software: CLion
"""
client: 10 20
server: 10 + 20
"""
import rospy
from rospy_tutorials.srv import AddTwoInts, AddTwoIntsRequest, AddTwoIntsResponse
def callback(request):
if not isinstance(request, AddTwoIntsRequest): return
a = request.a
b = request.b
# 业务逻辑处理
c = a + b
# 返回响应结果
response = AddTwoIntsResponse()
response.sum = c
return response
if __name__ == '__main__':
# 创建节点
rospy.init_node('server_node')
# server通讯的服务端server
# 服务端server
# 服务地址
service_name = '/hello/server'
# service_class,服务的数据类型
# handle,回调,客户端什么时候访问
server = rospy.Service(service_name, AddTwoInts, callback)
rospy.spin()
6.2 Server端调试
6.2.1 rosservice工具(命令行)
通过 rosservice list
命令可以帮助我们查询出当前运行的所有service
rosservice list
查询的结果中,我们可以得到对应的服务名称 /hello/server
通过查询的服务名称,来调用此服务
rosservice call /hello/server "a:1 b:3"
rosservice call
负责调用service。第一个参数是要调用的service的名称,后面的参数是调用时需要传入的参数。
6.2.2 rqt_service_caller工具(可视化)
通过命令呼出工具
rosrun rqt_service_caller rqt_service_caller
6.3 Client端创建
6.3.1 创建节点
rospy.init_node('client_node')
6.3.2 调用Service
# 确保servers是存在的,等待服务开启,阻塞代码
rospy.wait_for_service(service_name)
# 创建服务
client = rospy.ServiceProxy(service_name, AddTwoInts)
# 给server发请求
request = AddTwoIntsRequest()
request.a = 17
request.b = 8
response = client.call(request)
6.3.3 Client端实现
完整代码如下:
#!/usr/bin/env python
# -*- coding: utf-8 -*-
# @Time : 15/9/20 2:21 AM
# @Author : Chenan_Wang
# @File : client_node.py
# @Software: CLion
import rospy
from rospy_tutorials.srv import AddTwoInts, AddTwoIntsRequest, AddTwoIntsResponse
if __name__ == '__main__':
# 创建节点
rospy.init_node('client_node')
# 服务通讯的客户端client
# 服务名称地址
service_name = '/hello/server'
client = rospy.ServiceProxy(service_name, AddTwoInts)
# 确保servers是存在的,等待服务开启,阻塞代码
rospy.wait_for_service(service_name)
# 给server发请求
request = AddTwoIntsRequest()
request.a = 17
request.b = 8
response = client.call(request)
if isinstance(response, AddTwoIntsResponse):
print response.sum
rospy.spin()
6.4 Client端调试
通过已有的server来调试client
source devel/setup.bash
rosrun hello_service server_node.py
source devel/setup.bash
rosrun hello_service client_node.py
6.5 Service命令行工具
查询所有的Service
rosservice list
查询service详情
<code class="prism language-shell has-numbering">rosservice info 服务地址</code>
<code class="prism language-shell has-numbering"></code>
查询service传输的数据类型
<code class="prism language-shell has-numbering">rosservice <span class="token function">type</span> 服务地址 </code>
模拟client端调用服务
<code class="prism language-shell has-numbering">rosservcie call 服务地址 请求数据 </code>
查询service请求参数
<code class="prism language-shell has-numbering">rosservice args 服务地址 </code>
七、Service通讯练习