Note: This tutorial assumes that you have completed the previous tutorials: 检验简单的发布者和订阅者.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

编写简单的服务和客户端(Python)

Description: 本教程介绍如何用Python编写服务和客户端节点。

Tutorial Level: BEGINNER

Next Tutorial: 检验简单的服务和客户端

编写服务节点

这里,我们将创建简单的服务(Service)节点add_two_ints_server,该节点将接收两个整数,并返回它们的和。

将当前目录切换到之前的教程中创建的beginner_tutorials包中:

$ roscd beginner_tutorials

请确保你已经按照之前教程中的指示创建了本教程中需要的服务AddTwoInts.srv。(确保在页面顶部选对了所使用的构建工具)

代码

在beginner_tutorials包中创建scripts/add_two_ints_server.py文件并粘贴以下内容进去:

   1 #!/usr/bin/env python
   2 import roslib; roslib.load_manifest('beginner_tutorials')
   3 from beginner_tutorials.srv import *
   4 import rospy
   5 
   6 def handle_add_two_ints(req):
   7     print "Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b))
   8     return AddTwoIntsResponse(req.a + req.b)
   9 
  10 def add_two_ints_server():
  11     rospy.init_node('add_two_ints_server')
  12     s = rospy.Service('add_two_ints', AddTwoInts, handle_add_two_ints)
  13     print "Ready to add two ints."
  14     rospy.spin()
  15 
  16 if __name__ == "__main__":
  17     add_two_ints_server()

   1 #!/usr/bin/env python
   2 
   3 from __future__ import print_function
   4 
   5 from beginner_tutorials.srv import AddTwoInts,AddTwoIntsResponse
   6 import rospy
   7 
   8 def handle_add_two_ints(req):
   9     print("Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b)))
  10     return AddTwoIntsResponse(req.a + req.b)
  11 
  12 def add_two_ints_server():
  13     rospy.init_node('add_two_ints_server')
  14     s = rospy.Service('add_two_ints', AddTwoInts, handle_add_two_ints)
  15     print("Ready to add two ints.")
  16     rospy.spin()
  17 
  18 if __name__ == "__main__":
  19     add_two_ints_server()

别忘了给节点执行权限:

  • chmod +x scripts/add_two_ints_server.py

然后将以下内容添加到CMakeLists.txt文件。这样可以确保正确安装Python脚本,并使用合适的Python解释器。

catkin_install_python(PROGRAMS scripts/add_two_ints_server.py
  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

解释

现在,让我们把代码分解。

使用rospy编写服务的难度非常小。我们使用init_node()声明我们的节点,然后再声明我们的服务:

  12     s = rospy.Service('add_two_ints', AddTwoInts, handle_add_two_ints)

这声明了一个名为add_two_ints的新服务,其服务类型为AddTwoInts。所有的请求(request)都传递给了handle_add_two_ints函数。handle_add_two_intsAddTwoIntsRequest的实例调用,返回AddTwoIntsResponse实例。

就像订阅者中的例子一样,rospy.spin()可以防止代码在服务关闭之前退出。

编写客户端节点

代码

在beginner_tutorials包中创建scripts/add_two_ints_client.py文件并粘贴以下内容进去:

   1 #!/usr/bin/env python
   2 
   3 from __future__ import print_function
   4 
   5 import sys
   6 import rospy
   7 from beginner_tutorials.srv import *
   8 
   9 def add_two_ints_client(x, y):
  10     rospy.wait_for_service('add_two_ints')
  11     try:
  12         add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
  13         resp1 = add_two_ints(x, y)
  14         return resp1.sum
  15     except rospy.ServiceException as e:
  16         print("Service call failed: %s"%e)
  17 
  18 def usage():
  19     return "%s [x y]"%sys.argv[0]
  20 
  21 if __name__ == "__main__":
  22     if len(sys.argv) == 3:
  23         x = int(sys.argv[1])
  24         y = int(sys.argv[2])
  25     else:
  26         print(usage())
  27         sys.exit(1)
  28     print("Requesting %s+%s"%(x, y))
  29     print("%s + %s = %s"%(x, y, add_two_ints_client(x, y)))

别忘了给节点执行权限:

$ chmod +x scripts/add_two_ints_client.py

然后,在你的CMakeLists.txt中编辑catkin_install_python()调用,就像这样:

catkin_install_python(PROGRAMS scripts/add_two_ints_server.py scripts/add_two_ints_client.py
  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

解释

现在,让我们把代码分解。

客户端(用来调用服务)的代码也很简单。对于客户端来说不需要调用init_node()。我们首先调用:

  10     rospy.wait_for_service('add_two_ints')

这是一种很方便的方法,可以让在add_two_ints服务可用之前一直阻塞。

  12         add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)

这里我们为服务的调用创建了一个句柄(handle)。

  13         resp1 = add_two_ints(x, y)
  14         return resp1.sum

然后我们可以使用这个句柄,就像普通的函数一样调用它。

因为我们已经将服务的类型声明为AddTwoInts,它会为你生成AddTwoIntsRequest对象 (you're free to pass in your own instead)。如果调用失败,rospy.ServiceException将会抛出,所以你应该弄一个合适的try/except部分。

构建节点

我们使用CMake作为构建系统。是的,即使是Python节点也必须使用它。这是为了确保能为创建的消息和服务自动生成Python代码。

We also use a Makefile for a bit of convenience. roscreate-pkg automatically created a Makefile, so you don't have to edit it.

Now run make:

$ make

切换当前目录到你的catkin工作空间,然后运行catkin_make

# 在你的catkin工作空间中
$ cd ~/catkin_ws
$ catkin_make

现在你已经编写了一个简单的服务和客户端,开始检验简单的服务和客户端吧。

视频教程

下面的视频提供了一个关于ROS服务的小教程。

Wiki: cn/ROS/Tutorials/WritingServiceClient(python) (last edited 2020-12-28 06:41:12 by yakamoz423)