ROS Service¶
ROS Service概念¶
ROS Topic适合实现状态监控类的任务,但Topic通信存在一些缺陷:
- 无法确认发布信息是否被收到。
- 有些类型的消息(例如相机节点发布的消息),按照一定频率发布,通常会占用比较大的带宽,造成资源浪费。
ROS Service可以解决以上问题。
Service是ROS Node的通信方式之一
Service通信的特点为:
- Service使用 请求-查询式 的通信模型,这样的通信模型没有频繁的消息传递,没有高系统资源的占用,只有接受请求才执行服务,简单而且高效。
- Service通信实现的是 一对一 通信,每一个服务由一个节点发起,对这个服务的响应返回同一个节点;Service的信息流是双向的,不仅可以发送消息,同时还会有反馈。所有service包含两部分,Client与Server。
- Service是 同步 通信方式,Client发布请求后会在原地等等reply,直到Server处理完了请求并且完成了reply,Client才会继续执行;Client等待过程中,处于阻塞状态。
下图是ROS Node Service通信的图形化表示,我们可以看到Client Node和Server Node通过request-response的方式进行通信。
ROS Service 命令行工具¶
ROS提供了一些命令行工具帮助我们查看Service的信息,最常用的是:
rosservice list #列出当前正在运行的Services
rosservice call <service_name> <service_arguments> #调用指定的Service
更多ROS Service的命令行工具可通过在终端中输入 rosservice -h
查看
ROS Service示例¶
首先新建service_demo package,并创建scripts文件夹,在src空间执行以下操作:
catkin_create_pkg service_demo rospy std_msgs rospy_tutorials
cd service_demo
mkdir scripts
Service Server Node Demo
#!/usr/bin/python2
# coding: utf-8
import rospy
from rospy_tutorials.srv import *
def handle_add_two_ints(req):
print "Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b))
return AddTwoIntsResponse(req.a + req.b)
def add_two_ints_server():
rospy.init_node('add_two_ints_server') # 初始化Node
s = rospy.Service('add_two_ints', AddTwoInts, handle_add_two_ints) # 创建Service Server
print "Ready to add two ints."
rospy.spin()
if __name__ == "__main__":
add_two_ints_server()
Service Client Node Demo
#!/usr/bin/python2
# coding: utf-8
import sys
import rospy
from rospy_tutorials.srv import *
def add_two_ints_client(x, y):
rospy.wait_for_service('add_two_ints') # 阻塞直到server可用
try:
add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts) # 创建Service调用handle
resp1 = add_two_ints(x, y) # 调用Service
return resp1.sum
except rospy.ServiceException, e:
print "Service call failed: %s"%e
def usage():
return "Usage: rosrun <client_node_name> [x y]"
if __name__ == "__main__":
if len(sys.argv) == 3:
x = int(sys.argv[1])
y = int(sys.argv[2])
else:
print usage()
sys.exit(1)
print "Requesting %s+%s"%(x, y)
print "%s + %s = %s"%(x, y, add_two_ints_client(x, y))
使用ROS Service开发ROS应用需要注意的内容:
- ROS Service会阻塞程序流
- 在Service回调函数中只能进行能够快速完成的计算任务
- 进入Service回调流程后没有中途返回机制
自定义Service类型¶
Service文件
- ROS通过service文件定义Service
- Service文件通常位于<ros_package_name>/srv文件夹中
- Service文件的名字通常为<custom_message_type>.srv
- Service类型包含request、response两部分
自定义Service类型
现在,我们定义一个新的弧度角转换Service类型: RadianToAngle
要求包含:
- Request - 弧度值
- Response - 角度值
- Response - 转换成功标志位
我们可以通过以下指令创建这个新的Service类型:
首先创建srv文件:
roscd service_demo
mkdir srv
cd srv
touch RadianToAngle.srv
然后在新建的srv文件中输入以下内容:
float64 radian
---
float64 angle
bool success
编译构建自定义的Service类型
在上一部分我们定义了新的Service文件,新定义的Service经过编译构建之后才能在程序中使用。
首先修改package.xml文件,在package.xml文件中添加以下内容:
<build_depend>message_generation</build_depend>
<build_export_depend>message_generation</build_export_depend>
<exec_depend>message_runtime</exec_depend>
然后修改CMakeLists.txt文件,在CMakeLists.txt文件中相应的位置添加以下内容:
# 在find_package中添加message_generation
find_package(catkin REQUIRED COMPONENTS
rospy
rospy_tutorials
std_msgs
message_generation
)
# 在add_service_files中添加RadianToAngle.srv
add_service_files(
FILES
RadianToAngle.srv
)
# 去掉generate_messages的注释
generate_messages(
DEPENDENCIES
std_msgs
)
随后切换到tr_tutorial_ws顶层目录执行编译构建:
catkin build
编译完成之后:
source devel/setup.bash
我们可以通过 rossrv 命令行工具查看新定义的Service类型:
rossrv show service_demo/RadianToAngle
# 新定义的Service的内容
float64 radian
---
float64 angle
bool success
如果想查看更详细的描述,可以添加 -r 命令选项:
rossrv show service_demo/RadianToAngle -r
这样我们就可以在程序中使用自定义的Message类型了。
ROS Service练习¶
我们已经完成了Service Server、Client的构建及定义新的Service类型,接下来我们进行一个小练习,构建一个简单的ROS应用:
- 包含一个Service Server和一个Service Client
- Service Server提供将弧度转换为角度的Service
- Service Client向Server发出转换请求
ROS Service练习示例-Server:
#!/usr/bin/python2
# coding: utf-8
import rospy
from math import pi
from service_demo.srv import RadianToAngle, RadianToAngleRequest, RadianToAngleResponse
def radian_to_angel_server_callback(req):
res = RadianToAngleResponse()
res.angle = 180.0 / pi * req.radian
res.success = True
print "request radian: %f, response angle: %f"%(req.radian, res.angle)
return res
def radian_to_angle_server():
rospy.init_node('radian_to_angle_server_node')
radian_to_angle_server = rospy.Service('radian_to_angle', RadianToAngle, radian_to_angel_server_callback)
print "Ready to convert radian to angle"
rospy.spin();
if __name__ == '__main__':
radian_to_angle_server()
ROS Service练习示例-Client:
#!/usr/bin/python2
# coding: utf-8
import sys
import rospy
from service_demo.srv import *
def radian_to_angle_client(rad):
rospy.wait_for_service('radian_to_angle')
try:
radian_to_angle = rospy.ServiceProxy('radian_to_angle', RadianToAngle)
resp = radian_to_angle(rad)
if resp.success:
return resp.angle
except rospy.ServiceException, e:
print "Service call failed: %s"%e
if __name__ == '__main__':
if len(sys.argv) == 2:
r = float(sys.argv[1])
else:
print "Usage: rosrun <service_node_name> radian"
sys.exit(1)
print "radian: %f convert to angle is: %f"%(r,radian_to_angle_client(r))
关于如何创建自定义的Service类型的内容可参考以下链接: