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.

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

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

Tutorial Level: BEGINNER

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

编写服务节点

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

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

$ roscd beginner_tutorials

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

代码

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

   1 #include "ros/ros.h"
   2 #include "beginner_tutorials/AddTwoInts.h"
   3 
   4 bool add(beginner_tutorials::AddTwoInts::Request  &req,
   5          beginner_tutorials::AddTwoInts::Response &res)
   6 {
   7   res.sum = req.a + req.b;
   8   ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
   9   ROS_INFO("sending back response: [%ld]", (long int)res.sum);
  10   return true;
  11 }
  12 
  13 int main(int argc, char **argv)
  14 {
  15   ros::init(argc, argv, "add_two_ints_server");
  16   ros::NodeHandle n;
  17 
  18   ros::ServiceServer service = n.advertiseService("add_two_ints", add);
  19   ROS_INFO("Ready to add two ints.");
  20   ros::spin();
  21 
  22   return 0;
  23 }

解释

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

   1 #include "ros/ros.h"
   2 #include "beginner_tutorials/AddTwoInts.h"
   3 

beginner_tutorials/AddTwoInts.h是从我们之前创建的srv文件中生成的头文件。

   4 bool add(beginner_tutorials::AddTwoInts::Request  &req,
   5          beginner_tutorials::AddTwoInts::Response &res)

这个函数提供了AddTwoInts服务,它接受srv文件中定义的请求(request)和响应(response)类型,并返回一个布尔值。

   6 {
   7   res.sum = req.a + req.b;
   8   ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b);
   9   ROS_INFO("sending back response: [%ld]", (long int)res.sum);
  10   return true;
  11 }

此处,两个整数被相加,和已经存储在了响应中。然后记录一些有关请求和响应的信息到日志中。完成后,服务返回true

  18   ros::ServiceServer service = n.advertiseService("add_two_ints", add);

在这里,服务被创建,并在ROS中宣告。

编写客户端节点

代码

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

   1 #include "ros/ros.h"
   2 #include "beginner_tutorials/AddTwoInts.h"
   3 #include <cstdlib>
   4 
   5 int main(int argc, char **argv)
   6 {
   7   ros::init(argc, argv, "add_two_ints_client");
   8   if (argc != 3)
   9   {
  10     ROS_INFO("usage: add_two_ints_client X Y");
  11     return 1;
  12   }
  13 
  14   ros::NodeHandle n;
  15   ros::ServiceClient client = n.serviceClient<beginner_tutorials::AddTwoInts>("add_two_ints");
  16   beginner_tutorials::AddTwoInts srv;
  17   srv.request.a = atoll(argv[1]);
  18   srv.request.b = atoll(argv[2]);
  19   if (client.call(srv))
  20   {
  21     ROS_INFO("Sum: %ld", (long int)srv.response.sum);
  22   }
  23   else
  24   {
  25     ROS_ERROR("Failed to call service add_two_ints");
  26     return 1;
  27   }
  28 
  29   return 0;
  30 }

解释

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

  15   ros::ServiceClient client = n.serviceClient<beginner_tutorials::AddTwoInts>("add_two_ints");

这将为add_two_ints服务创建一个客户端。ros::ServiceClient对象的作用是在稍后调用服务。

  16   beginner_tutorials::AddTwoInts srv;
  17   srv.request.a = atoll(argv[1]);
  18   srv.request.b = atoll(argv[2]);

这里我们实例化一个自动生成的服务类,并为它的request成员赋值。一个服务类包括2个成员变量:requestresponse,以及2个类定义:RequestResponse

  19   if (client.call(srv))

此处实际上调用了服务。由于服务调用被阻塞,它将在调用完成后返回。如果服务调用成功,call()将返回true,并且srv.response中的值将是有效的。如果调用不成功,则call()将返回falsesrv.response的值将不可用。

构建节点

再来编辑一下beginner_tutorials里面的CMakeLists.txt:

$ rosed beginner_tutorials CMakeLists.txt

将下面的内容加载文件末尾:

rosbuild_add_executable(add_two_ints_server src/add_two_ints_server.cpp)
rosbuild_add_executable(add_two_ints_client src/add_two_ints_client.cpp)

这段代码将生成两个可执行程序"add_two_ints_server"和"add_two_ints_client",这两个可执行程序默认被放在"bin"文件夹下。

关于在ROS上面使用CMake的更多信息,可以参考CMakeLists 现在,运行make命令:

$ make

再来编辑一下beginner_tutorials里面的CMakeLists.txt文件,文件位于~/catkin_ws/src/beginner_tutorials/CMakeLists.txt,并将下面的代码添加在文件末尾:

https://raw.github.com/ros/catkin_tutorials/master/create_package_srvclient/catkin_ws/src/beginner_tutorials/CMakeLists.txt

  27 add_executable(add_two_ints_server src/add_two_ints_server.cpp)
  28 target_link_libraries(add_two_ints_server ${catkin_LIBRARIES})
  29 add_dependencies(add_two_ints_server beginner_tutorials_gencpp)
  30 
  31 add_executable(add_two_ints_client src/add_two_ints_client.cpp)
  32 target_link_libraries(add_two_ints_client ${catkin_LIBRARIES})
  33 add_dependencies(add_two_ints_client beginner_tutorials_gencpp)

这将创建两个可执行文件add_two_ints_serveradd_two_ints_client,默认情况下,它们将被放到软件包目录下的devel空间中,即~/catkin_ws/devel/lib/<package name>。你可以直接调用可执行文件,也可以使用rosrun来调用它们。它们没有被放在<prefix>/bin中,因为这样在将软件包安装到系统时会污染PATH环境变量。但如果你希望在安装时将可执行文件放在PATH中,可以配置安装目标,参见CMakeLists.txt

现在可以运行catkin_make

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

如果你的构建过程因为某些原因而失败:

  • 输入rosls beginner_tutorials/srv_gen/cpp/include/beginner_tutorials/命令,并检查看看client和server的.cpp文件里include进去的是否与.h文件相匹配。

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

视频教程

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

Wiki: cn/ROS/Tutorials/WritingServiceClient(c++) (last edited 2020-12-28 01:59:58 by yakamoz423)