3.7 服务中的Server和Client
服务(Service)是节点之间同步通信的一种方式,允许客户端(Client)节点发布请求(Request),由服务端(Server)节点处理后反馈应答(Response)。
3.7.1 乌龟例程中的服务
乌龟例程提供了不少设置功能,这些设置都以服务的形式提供。在乌龟例程运行状态下,使用如下命令查看系统中的服务列表(见图3-29):
$ rosservice list
图3-29 查看乌龟例程中的服务列表
可以使用代码或者终端对列表中的服务进行调用。例如使用以下命令调用“/spawn”服务新生一只乌龟:
$ rosservice call /spawn "x: 8.0 y: 8.0 theta: 0.0 name: 'turtle2'"
服务的请求数据是新生乌龟的位置、姿态以及名称,调用成功后仿真器中就会诞生一只新的乌龟(见图3-30)。
图3-30 服务调用成功后,产生一只新的乌龟
终端中会打印服务反馈的应答数据,即新生乌龟的名称,如图3-31所示。
图3-31 服务调用成功后的应答数据
从乌龟仿真例程中的服务可以看到,服务一般分为服务端(Server)和客户端(Client)两个部分,Client负责发布请求数据,等待Server处理;Server负责处理相应的功能,并且返回应答数据。
我们以一个简单的加法运算为例,具体研究ROS中的服务应用。在该例程中,Client发布两个需要相加的int类型变量,Server节点接收请求后完成运算并返回加法运算结果。
3.7.2 如何自定义服务数据
下面从自定义服务数据开始。与话题消息类似,ROS中的服务数据可以通过srv文件进行语言无关的接口定义,一般放置在功能包根目录下的srv文件夹中。该文件包含请求与应答两个数据域,数据域中的内容与话题消息的数据类型相同,只是在请求与应答的描述之间,需要使用“---”进行分割。
针对加法运算例程中的服务需求,创建一个定义服务数据类型的srv文件learning_communication/srv/AddTwoInts.srv:
int64 a int64 b --- int64 sum
该srv文件的内容较为简单,在服务请求的数据域中定义了两个int64类型的变量a和b,用来存储两个加数;又在服务应答的数据域中定义了一个int64类型的变量sum,用来存储“a+b”的结果。
完成服务数据类型的描述后,与话题消息一样,还需要在功能包的package.xml和CMakeLists.txt文件中配置依赖与编译规则,在编译过程中将该描述文件转换成编程语言所能识别的代码。
打开package.xml文件,添加以下依赖配置(在3.6.6节定义话题消息的时候已经添加):
<build_depend>message_generation</build_depend> <run_depend>message_runtime</run_depend>
打开CMakeLists.txt文件,添加如下配置(message_generation在3.6.6节也已经添加):
find_package(catkin REQUIRED COMPONENTS geometry_msgs roscpp rospy std_msgs message_generation ) add_service_files( FILES AddTwoInts.srv )
message_generation包不仅可以针对话题消息产生相应的代码,还可以根据服务消息的类型描述文件产生相关的代码。
功能包编译成功后,在服务的Server节点和Client节点的代码实现中就可以直接调用这些定义好的服务消息了。
接下来我们就编写Server和Client节点的代码,完成两数相加求和的服务过程。
3.7.3 如何创建Server
首先创建Server节点,提供加法运算的功能,返回求和之后的结果。实现该节点的源码文件learning_communication/src/server.cpp内容如下:
#include "ros/ros.h" #include "learning_communication/AddTwoInts.h" // service回调函数,输入参数req,输出参数res bool add(learning_communication::AddTwoInts::Request &req, learning_communication::AddTwoInts::Response &res) { // 将输入参数中的请求数据相加,结果放到应答变量中 res.sum = req.a + req.b; ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b); ROS_INFO("sending back response: [%ld]", (long int)res.sum); return true; } int main(int argc, char **argv) { // ROS节点初始化 ros::init(argc, argv, "add_two_ints_server"); // 创建节点句柄 ros::NodeHandle n; // 创建一个名为add_two_ints的server,注册回调函数add() ros::ServiceServer service = n.advertiseService("add_two_ints", add); // 循环等待回调函数 ROS_INFO("Ready to add two ints."); ros::spin(); return 0; }
剖析以上代码中Server节点的实现过程。
1.头文件部分
#include "ros/ros.h" #include "learning-communication/AddTwoInts.h"
使用ROS中的服务,必须包含服务数据类型的头文件,这里使用的头文件是learning_communication/AddTwoInts.h,该头文件根据我们之前创建的服务数据类型的描述文件AddTwoInts.srv自动生成。
2.主函数部分
ros::ServiceServer service = n.advertiseService("add_two_ints", add);
主函数部分相对简单,先初始化节点,创建节点句柄,重点是要创建一个服务的Server,指定服务的名称以及接收到服务数据后的回调函数。然后开始循环等待服务请求;一旦有服务请求,Server就跳入回调函数进行处理。
3.回调函数部分
bool add(learning_communication::AddTwoInts::Request &req, learning_communication::AddTwoInts::Response &res)
回调函数是真正实现服务功能的部分,也是设计的重点。add()函数用于完成两个变量相加的功能,其传入参数便是我们在服务数据类型描述文件中声明的请求与应答的数据结构。
{ res.sum = req.a + req.b; ROS_INFO("request: x=%ld, y=%ld", (long int)req.a, (long int)req.b); ROS_INFO("sending back response: [%ld]", (long int)res.sum); return true; }
在完成加法运算后,求和结果会放到应答数据中,反馈到Client,回调函数返回true。
服务中的Server类似于话题中的Subscriber,实现流程如下:
·初始化ROS节点。
·创建Server实例。
·循环等待服务请求,进入回调函数。
·在回调函数中完成服务功能的处理并反馈应答数据。
3.7.4 如何创建Client
创建Client节点,通过终端输入的两个加数发布服务请求,等待应答结果。该节点实现代码learning_communication/src/client.cpp的内容如下:
#include <cstdlib> #include "ros/ros.h" #include "learning_communication/AddTwoInts.h" int main(int argc, char **argv) { // ROS节点初始化 ros::init(argc, argv, "add_two_ints_client"); // 从终端命令行获取两个加数 if (argc != 3) { ROS_INFO("usage: add_two_ints_client X Y"); return 1; } // 创建节点句柄 ros::NodeHandle n; // 创建一个client,请求add_two_int service // service消息类型是learning_communication::AddTwoInts ros::ServiceClient client = n.serviceClient<learning_communication::AddTwoInts> ("add_two_ints"); // 创建learning_communication::AddTwoInts类型的service消息 learning_communication::AddTwoInts srv; srv.request.a = atoll(argv[1]); srv.request.b = atoll(argv[2]); // 发布service请求,等待加法运算的应答结果 if (client.call(srv)) { ROS_INFO("Sum: %ld", (long int)srv.response.sum); } else { ROS_ERROR("Failed to call service add_two_ints"); return 1; } return 0; }
下面剖析以上代码中Client节点的实现过程。
1.创建Client
ros::ServiceClient client = n.serviceClient<learning_communication::AddTwoInts> ("add_two_ints");
首先需要创建一个add_two_ints的Client实例,指定服务类型为learning_communication::AddTwoInts。
2.发布服务请求
learning_communication::AddTwoInts srv; srv.request.a = atoll(argv[1]); srv.request.b = atoll(argv[2]);
然后实例化一个服务数据类型的变量,该变量包含两个成员:request和response。将节点运行时输入的两个参数作为需要相加的两个整型数存储到变量中。
if (client.call(srv))
接着进行服务调用。该调用过程会发生阻塞,调用成功后返回true,访问srv.response即可获取服务请求的结果。如果调用失败会返回false,srv.response则不可使用。
服务中的Client类似于话题中的Publisher,实现流程如下:
·初始化ROS节点。
·创建一个Client实例。
·发布服务请求数据。
·等待Server处理之后的应答结果。
3.7.5 编译功能包
代码已经编写完成,接下来编辑CMakeLists.txt文件,加入如下编译规则,与编译Publisher和Subscriber时的配置类似:
add_executable(server src/server.cpp) target_link_libraries(server ${catkin_LIBRARIES}) add_dependencies(server ${PROJECT_NAME}_gencpp) add_executable(client src/client.cpp) target_link_libraries(client ${catkin_LIBRARIES}) add_dependencies(client ${PROJECT_NAME}_gencpp)
现在就可以使用catkin_make命令编译功能包了。
3.7.6 运行Server和Client
激动人心的时刻终于到了,运行之前别忘记设置环境变量。然后就可以运行编译生成的Server和Client节点了。
1.启动roscore
在运行节点之前,首先需要确保ROS Master已经成功启动:
$ roscore
2.运行Server节点
打开终端,使用如下命令运行Server节点:
$ rosrun learning_communication server
如果运行正常,终端中应该会显示如图3-32所示的信息。
图3-32 Server节点启动后的日志信息
3.运行Client节点
打开一个新的终端,运行Client节点,同时需要输入加法运算的两个加数值:
$ rosrun learning_communication client 3 5
Client发布服务请求,Server完成服务功能后反馈结果给Client。在Server和Client的终端中分别可以看到如图3-33和图3-34所示的日志信息。
图3-33 Client启动后发布服务请求,并成功接收到反馈结果
图3-34 Server接收到服务调用后完成加法求解,并将结果反馈给Client