多节点服务通信

话题通信可以实现多个ROS节点之间数据的单向传输,使用这种异步通信机制,发布者无法准确知道订阅者是否收到消息,本讲我们将一起学习ROS另外一种常用的通信方法——**服务**,可以实现类似**你问我答的同步通信**效果。



通信模型

在之前的课程中,我们通过一个节点驱动相机,发布图像话题,另外一个节点订阅图像话题,并实现对其中红色物体的识别,此时我们可以按照图像识别的频率,周期得到物体的位置。
这个位置信息可以继续发给机器人的上层应用使用,比如可以跟随目标运动,或者运动到目标位置附近。此时,我们并不需要这么高的频率一直订阅物体的位置,而是更希望在需要这个数据的时候,发一个查询的请求,然后尽快得到此时目标的最新位置。



这样的通信模型和话题单向传输有所不同,变成了发送一个请求,反馈一个应答的形式,好像是你问我答一样,这种通信机制在ROS中成为**服务,Service**。



客户端/服务器模型

从服务的实现机制上来看,这种你问我答的形式叫做**客户端/服务器模型**,简称为CS模型,客户端在需要某些数据的时候,针对某个具体的服务,发送请求信息,服务器端收到请求之后,就会进行处理并反馈应答信息。

这种通信机制在生活中也很常见,比如我们经常浏览的各种网页,此时你的电脑浏览器就是客户端,通过域名或者各种操作,向网站服务器发送请求,服务器收到之后返回需要展现的页面数据。



同步通信
这个过程一般要求越快越好,假设服务器半天没有反应,你的浏览器一直转圈圈,那有可能是服务器宕机了,或者是网络不好,所以相比话题通信,在服务通信中,客户端可以通过接收到的应答信息,判断服务器端的状态,我们也称之为同步通信。 一对多通信
比如古月居这个网站,服务器是唯一存在的,并没有多个完全一样的古月居网站,但是可以访问古月居网站的客户端是不唯一的,大家每一个人都可以看到同样的界面。所以服务通信模型中,服务器端唯一,但客户端可以不唯一。



 服务接口

和话题通信类似,服务通信的核心还是要传递数据,数据变成了两个部分,一个**请求的数据**,比如请求苹果位置的命令,还有一个**反馈的数据**,比如反馈苹果坐标位置的数据,这些数据和话题消息一样,在ROS中也是要标准定义的,话题使用.msg文件定义,服务使用的是.srv文件定义,后续我们会给大家介绍定义的方法。



 编程方法

了解了服务通信的原理,接下来我们就要开始编写代码啦,我们尝试通过服务实现一个加法求解器的功能。



 运行示例程序

当我们需要计算两个加数的求和结果时,就通过客户端节点,将两个加数封装成请求数据,针对服务“add_two_ints”发送出去,提供这个服务的服务器端节点,收到请求数据后,开始进行加法计算,并将求和结果封装成应答数据,反馈给客户端,之后客户端就可以得到想要的结果啦。

我们一起操作下这个例程。
bash
$ source /opt/tros/local_setup.bash
$ source install/local_setup.bash
$ ros2 run learning_service_cpp server
$ ros2 run learning_service_cpp client 2 3

话题和服务是最为常用的两种数据通信方法,前者适合传感器、控制指令等周期性、单向传输的数据,后者适合一问一答,同步性要求更高的数据,比如获取机器视觉识别到的目标位置。



 代码解析

服务器端add_two_ints_server.cpp:
bash
#include "rclcpp/rclcpp.hpp"
#include "learning_service_cpp/srv/add_two_ints.hpp"

#include <memory>

void add(const std::shared_ptr<learning_service_cpp::srv::AddTwoInts::Request> request,
          std::shared_ptr<learning_service_cpp::srv::AddTwoInts::Response>      response)
{
  response->sum = request->a + request->b;
  RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Incoming request\na: %ld" " b: %ld",
                request->a, request->b);
  RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "sending back response: [%ld]", (long int)response->sum);
}

int main(int argc, char **argv)
{
  rclcpp::init(argc, argv);

  std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_server");

  rclcpp::Service<learning_service_cpp::srv::AddTwoInts>::SharedPtr service =
    node->create_service<learning_service_cpp::srv::AddTwoInts>("add_two_ints", &add);

  RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Ready to add two ints.");

  rclcpp::spin(node);
  rclcpp::shutdown();
}


客户端add_two_ints_client.cpp:
c++
#include "rclcpp/rclcpp.hpp"
#include "learning_service_cpp/srv/add_two_ints.hpp"

#include <chrono>
#include <cstdlib>
#include <memory>

using namespace std::chrono_literals;

int main(int argc, char **argv)
{
  rclcpp::init(argc, argv);

  if (argc != 3) {
      RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "usage: add_two_ints_client X Y");
      return 1;
  }

  std::shared_ptr<rclcpp::Node> node = rclcpp::Node::make_shared("add_two_ints_client");
  rclcpp::Client<learning_service_cpp::srv::AddTwoInts>::SharedPtr client =
    node->create_client<learning_service_cpp::srv::AddTwoInts>("add_two_ints");

  auto request = std::make_shared<learning_service_cpp::srv::AddTwoInts::Request>();
  request->a = atoll(argv[1]);
  request->b = atoll(argv[2]);

  while (!client->wait_for_service(1s)) {
    if (!rclcpp::ok()) {
      RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Interrupted while waiting for the service. Exiting.");
      return 0;
    }
    RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "service not available, waiting again...");
  }

  auto result = client->async_send_request(request);
  // Wait for the result.
  if (rclcpp::spin_until_future_complete(node, result) ==
    rclcpp::FutureReturnCode::SUCCESS)
  {
    RCLCPP_INFO(rclcpp::get_logger("rclcpp"), "Sum: %ld", result.get()->sum);
  } else {
    RCLCPP_ERROR(rclcpp::get_logger("rclcpp"), "Failed to call service add_two_ints");
  }

  rclcpp::shutdown();
  return 0;
}