ROS服务与客户端编写详解

说明

本文中包括服务、客户端等名称,其中服务包括两重含义,既可以理解为与客户端相对应的服务器,又可以理解为在服务器与客户端之间传递数据的格式,需根据上下文进行理解。

srv文件

srv文件是ROS服务与客户端机制中传递数据的格式,包括请求与响应两个部分,请求部分是客户端传递给服务的数据,响应部分则是服务返回给客户端的数据。

srv文件会在catkin_make后自动生成一个类,这个类以“软件包名称::服务名”命名,使用这个类需要引入头文件“软件包名称/服务名.h”(此处服务名指数据格式,与srv文件名相同),类中包含两个成员变量request和response,以及两个类定义Request和Response。成员变量request和response通过“.”运算符,可取得srv服务中请求或响应部分的具体值,以参与运算;而类Request和Response主要用于声明变量,以供在函数间传递参数。

服务

在服务中(此处服务指与客户端对应的服务器),需要完成如下内容:

  • 在主函数中
    • 初始化ROS,并指定节点名称
    • 为节点创建句柄
    • 创建服务,同时指出服务名和服务中执行功能的回调函数名称
    • 循环运行回调函数
  • 在主函数外
    • 编写回调函数

在服务中,一些重要的变量如下:

  • 节点名,通过ros::init指定运行节点时用到的节点名,用引号包围,对应下图中的"kinematics_server"

  • 句柄,声明句柄后,可利用句柄通过“.”运算符调用advertiseService方法,创建服务,对应下图中的n

  • 服务名,通过上述advertiseService方法指定服务名,用引号包围,创建客户端时需要指明对应的服务名,对应下图中的"trans_pose"

  • 服务(服务器)对象,属于ros::ServiceServer类型,作为advertiseService方法的返回值,对应下图中的service

  • 回调函数,同样在advertiseService方法中指出,无需引号,当服务被请求时回调函数被执行以进行响应,回调函数通常需要以服务(此处服务指srv表明的数据格式)自动生成的类中定义的类型变量作为形参,从而实现根据服务传递的数据运算并返回运算结果,对应下图中无引号的trans_pose

客户端

在客户端中,需要完成如下内容:

  •  在主函数中
    • 初始化ROS,并指定节点名称
    • 为节点创建句柄
    • 创建客户端,同时指出此客户端请求的服务(指与客户端对应的服务)名称
    • 声明服务类对象,通过此对象引用服务(指srv文件)中的请求与响应数据
    • 调用服务,传入上述声明的服务类对象

在客户端中,一些重要的名称与变量如下:

节点名,通过ros::init指定运行节点时用到的节点名,用引号包围,对应下图中的"kinematics_client"

  • 句柄,声明句柄后,可利用句柄通过“.”运算符调用serviceClient方法,创建客户端,对应下图中的n

  • 服务名,在上述创建客户端的serviceClient方法中需要指明客户端所请求的服务名,用引号包围,对应下图中的"trans_pose"

  • 客户端对象,属于ros::ServiceClient类型,作为serviceClient方法的返回值,其具有call方法可用于调用服务,对应下图中的client

  • 服务类型,在上述创建客户端的serviceClient方法中需要指明客户端所请求的服务类型,即传递的数据类型,用尖括号包围,对应下图中的<kinematics_demo::trans>

  • 服务类(srv文件生成的类)对象,用于引用服务(srv文件)中的请求与响应数据,对应下图中的srv

附:

srv文件

float64 init_x
float64 init_y
float64 init_z
float64 delta_x
float64 delta_y
float64 delta_z
---
float64 x
float64 y
float64 z

服务

// 包括了ROS常用的头文件
#include "ros/ros.h"

// 创建srv文件时生成的头文件,其中kinematics_demo为软件包名称,trans为srv文件名称,并在其后加上.h扩展名
#include "kinematics_demo/trans.h"

// 软件包名与srv文件名共同组成一个类名(kinematics_demo::trans),此类包括两个成员变量request、response和两个类定义Request、Response
// 服务中执行主要功能的回调函数的原型
bool trans_pose(kinematics_demo::trans::Request &req,
                kinematics_demo::trans::Response &res);

int main(int argc, char **argv)
{
    // 初始化ROS,并指定节点名称为kindmatics_sever
    ros::init(argc, argv, "kinematics_server");

    // 为节点创建句柄n
    ros::NodeHandle n;

    // 创建名称是trans_pose的服务,并注册回调函数trans_pose
    // 第一个trans_pose为服务名称,第二个trans_pose为回调函数名
    ros::ServiceServer service = n.advertiseService("trans_pose", trans_pose);
    ROS_INFO("Kinematics server");

    // 循环等待回调函数
    ros::spin();

    return 0;
}

bool trans_pose(kinematics_demo::trans::Request &req,
                kinematics_demo::trans::Response &res)
{
    res.x = req.init_x + req.delta_x;
    res.y = req.init_y + req.delta_y;
    res.z = req.init_z + req.delta_z;
    
    ROS_INFO("Pose before trans: (%f, %f, %f)", (double)req.init_x, (double)req.init_y, (double)req.init_z);
    ROS_INFO("Pose trans:        (%f, %f, %f)", (double)req.delta_x, (double)req.delta_y, (double)req.delta_z);
    ROS_INFO("Pose after trans:  (%f, %f, %f)", (double)res.x, (double)res.y, (double)res.z);

    return true;
}

客户端

// 包括了ROS常用的头文件
#include "ros/ros.h"
// 创建srv文件时生成的头文件,其中kinematics_demo为软件包名称,trans为srv文件名称,并在其后加上.h扩展名
#include "kinematics_demo/trans.h"
#include <cstdlib>

// 第一个形参argc(argument counter)表示main函数的参数个数
// 第二个形参argv(argument value)表示main函数的参数值
// 也可写为int main(int argc, char *argv[]),即由指针组成的数组,数组中每个元素都是指向char的指针
// 当不带参数运行主函数时,操作系统向主函数传递的参数argc为1,而argv[0](是一个指针)指向程序的路径及名称
// 当带参数运行主函数时,操作系统向主函数传递的参数argc为1加上参数个数,argv[0]意义不变,从arg[1]开始依次指向参数字符串

int main(int argc, char **argv)
{
    // 初始化ROS,并指定节点名称为kindmatics_client
    ros::init(argc, argv, "kinematics_client");

    // 当参数个数不为7(即未传入6个参数,与默认的1个参数共7个)
    if (argc != 7)
    {
        ROS_INFO("usage: kinematics_client init_x, init_y, init_z, delta_x, delta_y, delta_z");
        return 1;
    }

    // 为节点创建句柄n
    ros::NodeHandle n;

    // 为名称是trans_pose的服务创建客户端,并赋给名称为client的ros::ServiceClient的对象
    // 尖括号中为<软件包名::srv文件名>
    ros::ServiceClient client = n.serviceClient<kinematics_demo::trans>("trans_pose");
    
    // 实例化一个自动生成的服务类,即声明一个kinematics_demo::trans对象srv
    // *注:此处服务的意义与服务器的服务并不相同,此服务强调服务内容而非动作,与srv文件所表示的服务相同
    // 即软件包名与srv文件名二者共同组成一个类名,用此类名声明一个对象srv 
    kinematics_demo::trans srv;

    // 上面实例化的名为srv的服务类,包括两个成员变量request、response和两个类定义Request、Response
    // 为request成员赋值
    srv.request.init_x = atof(argv[1]);
    srv.request.init_y = atof(argv[2]);
    srv.request.init_z = atof(argv[3]);
    srv.request.delta_x = atof(argv[4]);
    srv.request.delta_y = atof(argv[5]);
    srv.request.delta_z = atof(argv[6]);

    // 客户端调用服务
    if(client.call(srv))
    {
        ROS_INFO("Pose after trans: (%f, %f, %f)", (double)srv.response.x, (double)srv.response.y, (double)srv.response.z);
    }
    else
    {
        ROS_ERROR("Failed to call service");
        return 1;
    }
    
    return 0;
}
posted @ 2021-07-15 16:48  溪嘉嘉  阅读(1391)  评论(0编辑  收藏  举报