↔️

ROS 2とgRPCのデータ送受信アプリを設計・実装する

2024/12/18に公開

海洋ロボコンをやってた人です。
ROS 2アドカレには3年目の投稿になります。

シリーズ1 22日目にもネタがありますが、今年度中に記事消化したい内容だったのでシリーズ2にも記事投稿することにしました。シリーズ1で元々予定していた内容よりも、別の内容でアドカレ投稿するという異例の試みです(汗)。

脱線しましたが本記事では、gRPCを使ったデータ送受信ならびにROS 2へのインテグを行ってみたので、備忘録として記事にまとめます。

記事のゴールは、gRPCの実装基礎とROS 2へのインテグ実施について学ぶことです。

通信フレームワークでgRPCを初めて導入してみたい方を対象としています。

誤記等あればご指摘ください、どうぞよろしくお願いいたします。


本記事で使用するプログラムは下記にまとめています。

https://github.com/tasada038/ros2_grpc_server

1. What is gRPC?

1.1. Introduction of gRPC

gRPC uses protobuf (protocol buffers) as the Interface Definition Language (IDL) to define the API interface (service definition).

gRPC とは、API インターフェース (サービス定義) を定義するために、インターフェース定義言語 (IDL) として protobuf (プロトコル バッファー) を使用する手法になります。

  • Remote Procedure Call (RPC):遠隔手続き呼び出し
  • Protocol Buffers(.proto):IDL間でデータやり取りするためのデータシリアライズフォーマット

を使用することで.protoファイル内でデータ構造を定義でき、このデータをエンコード/デコードして送受信することになります。

フレームワークの構成としては、gRPCサーバーの起動し、複数のクライアントからRequest/Responseを行うクライアント-サーバー通信モデルを採用しています。

https://grpc.io/docs/what-is-grpc/introduction/#overview

1.2. Pros vs. Cons

他の通信フレームワークと比較してgRPCは以下のメリットがあります。

メリット 説明
HTTP/2対応 ヘッダー圧縮、マルチプレクシング、サーバープッシュにより高速かつ効率的。
高速データ通信 Protocol Buffersによる軽量・高速なシリアライズでパフォーマンス向上。
ストリーミング 双方向ストリーミングに対応し、リアルタイム通信が容易。
自動コード生成 .protoファイルからサーバー・クライアントコードを自動生成可能。
多言語サポート C++, Python, Java, Goなど、多くの言語に対応。

その他gRPCについては下記も参照してください。

https://qiita.com/S4nTo/items/0ff0445542538ef49a05

https://qiita.com/mogamin3/items/7698ee3336c70a482843

2. How to use gRPC

ここからはgRPCのインストールから使い方までを記載していきます。

2.1. Build and install gRPC and Protocol Buffers

https://grpc.io/docs/languages/cpp/quickstart/

# gRPCリポジトリのクローン(サブモジュールとしてProtobufも含む)
git clone --recurse-submodules -b v1.48.0 https://github.com/grpc/grpc
cd grpc

# サブモジュール(Protobuf含む)を初期化
git submodule update --init

# gRPCおよびProtobufをビルド
mkdir -p cmake/build
cd cmake/build
cmake ../..
make -j4

# インストール(システムにインストールする場合はsudoが必要)
sudo make install
sudo apt update
sudo apt install -y build-essential autoconf libtool pkg-config
sudo apt install -y libgrpc++-dev protobuf-compiler-grpc
sudo apt install -y libprotobuf-dev

2.2 Coding gRPC in C++

2.2.1. Coding proto file

まずは.protoファイルを作成し、データ構造を定義していきます。

pose_messages.proto
syntax = "proto3";

package pose_messages;

// ========== Message Definitions ==========
message Pose {
  double x = 1;
  double y = 2;
  double theta = 3;
}

message Vector3 {
  double x = 1;
  double y = 2;
  double z = 3;
}

message Quaternion {
  double x = 1;
  double y = 2;
  double z = 3;
  double w = 4;
}

// ========== Service Definitions ==========
service PoseService {
  rpc SendPose(Pose) returns (Pose);
  rpc SendVector(Vector3) returns (Vector3);
  rpc SendQuaternion(Quaternion) returns (Quaternion);
}

ここでは、メッセージとして

  • Pose
  • Vector3
  • Quaternion

gRPCの利用できるサービスとして

  • SendPose
  • SendVector
  • SendQuaternion

を定義しています。

ここで定義したサービス(上述の場合service PoseService)は

  • サーバー側:.protoファイルでファイルを元にサービスを実装
  • クライアント側:.protoファイルを元に再生されたスタブを使用しサーバーへリクエスト送信

という形で利用されます。

2.2.2. Coding server file

続いて、サーバー側の実装をします。

pose_server.cpp
#include <iostream>
#include <memory>
#include <string>
#include <grpcpp/grpcpp.h>
#include "pose_messages.grpc.pb.h"

using grpc::Server;
using grpc::ServerBuilder;
using grpc::ServerContext;
using grpc::Status;
using pose_messages::Pose;
using pose_messages::Vector3;
using pose_messages::Quaternion;
using pose_messages::PoseService;

// Implementation of the PoseService gRPC service.
class PoseServiceImpl final : public PoseService::Service {
public:
    Status SendPose(ServerContext* context, const Pose* request, Pose* reply) override {
        std::cout << "Received Pose: (" << request->x() << ", " << request->y() << ", " << request->theta() << ")" << std::endl;
        *reply = *request;
        return Status::OK;
    }

    Status SendVector(ServerContext* context, const Vector3* request, Vector3* reply) override {
        std::cout << "Received Vector: (" << request->x() << ", " << request->y() << ", " << request->z() << ")" << std::endl;
        *reply = *request;
        return Status::OK;
    }

    Status SendQuaternion(ServerContext* context, const Quaternion* request, Quaternion* reply) override {
        std::cout << "Received Quaternion: (" << request->x() << ", " << request->y() << ", " << request->z() << ", " << request->w() << ")" << std::endl;
        *reply = *request;
        return Status::OK;
    }
};

// Function to start the gRPC server.
void RunServer() {
    std::string server_address("0.0.0.0:50051");
    PoseServiceImpl service;

    ServerBuilder builder;
    builder.AddListeningPort(server_address, grpc::InsecureServerCredentials());
    builder.RegisterService(&service);
    std::unique_ptr<Server> server(builder.BuildAndStart());
    std::cout << "Server listening on " << server_address << std::endl;

    server->Wait();
}

int main(int argc, char** argv) {
    RunServer();
    return 0;
}

サーバー側では、.protoファイルでサービス定義(Service Definitions)した各サービスのリクエストに対してどのような処理を行うかを記述します。

これをクラス内で記述し、void RunServer()でgRPCサーバーをビルド、実行するように実装します。

ここでは各サービスに対して、コンソールログとステータスを返すようにしています。

2.2.3. Coding clinet file

最後にクライアント側のファイルを作成します。

pose_client.cpp
#include <iostream>
#include <memory>
#include <string>
#include <grpcpp/grpcpp.h>
#include "pose_messages.grpc.pb.h"

using grpc::Channel;
using grpc::ClientContext;
using grpc::Status;
using pose_messages::Pose;
using pose_messages::Vector3;
using pose_messages::Quaternion;
using pose_messages::PoseService;

// Class representing a gRPC client for sending Pose messages.
class PoseClient {
public:
    PoseClient(std::shared_ptr<Channel> channel) : stub_(PoseService::NewStub(channel)) {}

    void SendPose(double x, double y, double theta) {
        Pose request;
        request.set_x(x);
        request.set_y(y);
        request.set_theta(theta);

        Pose reply;
        ClientContext context;

        Status status = stub_->SendPose(&context, request, &reply);

        if (status.ok()) {
            std::cout << "Pose sent: (" << reply.x() << ", " << reply.y() << ", " << reply.theta() << ")" << std::endl;
        } else {
            std::cout << "Error sending Pose: " << status.error_message() << std::endl;
        }
    }

private:
    std::unique_ptr<PoseService::Stub> stub_;
};


int main(int argc, char** argv) {
    /* arguments x, y, and theta */
    if (argc != 4) {
        std::cerr << "Usage: pose_client <x> <y> <theta>" << std::endl;
        return 1;
    }
    double x = std::stod(argv[1]);
    double y = std::stod(argv[2]);
    double theta = std::stod(argv[3]);
    /* end arguments version */
    // ./pose_client 1.0 3.0 3.14

    PoseClient client(grpc::CreateChannel("localhost:50051", grpc::InsecureChannelCredentials()));
    client.SendPose(x, y, theta);
    // client.SendPose(1.0, 3.0, 3.14);
    return 0;
}

クライアント側は.protoファイルを元に再生されたスタブを使用し、サーバーへリクエストを送信するため、class PoseClientでスタブ定義を行い、SendPoseサービスとしてx, y, thetaの値をリクエストするように定義します。

スタブ定義したサービスは、サーバーチャンネル(localhost:5051)に対して、リクエストを投げるようにmain文で記述します。

これがgRPCの基礎的な実装になります。

2.2.4. Coding CMakeLists.txt

最後にCMakeの記述も行います。

.protoファイルからC++コードを生成する場合、コマンドラインから--grpc_outを利用して自動生成するのですが、C++ファイルのビルド毎に.protoファイルもコード生成できるようにするのが望ましいです。

なので、CMakeLists.txt側で下記を追加します。

CMakeLists.txt
# 必要なパッケージを探す
find_package(Protobuf REQUIRED)
find_package(gRPC CONFIG REQUIRED)

# .protoファイルを指定
set(PROTO_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/proto")
set(PROTO_SRC "${PROTO_SRC_DIR}/grpc_sample.proto" "${PROTO_SRC_DIR}/pose_messages.proto")

# gRPC C++プラグインを指定
set(GRPC_CPP_PLUGIN_EXECUTABLE $<TARGET_FILE:gRPC::grpc_cpp_plugin>)

# ヘッダーファイルとソースファイルの出力ディレクトリを指定
set(GENERATED_PROTO_HDR_DIR "${CMAKE_CURRENT_SOURCE_DIR}/include")
set(GENERATED_PROTO_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src")

# .protoファイルからC++コードを生成
protobuf_generate_cpp(PROTO_SRCS PROTO_HDRS ${PROTO_SRC})

# .protoファイルからC++コードを生成
foreach(proto_file ${PROTO_SRC})
    get_filename_component(proto_name ${proto_file} NAME_WE)
    add_custom_command(
        OUTPUT ${GENERATED_PROTO_HDR_DIR}/${proto_name}.grpc.pb.cc ${GENERATED_PROTO_HDR_DIR}/${proto_name}.grpc.pb.h
        COMMAND ${Protobuf_PROTOC_EXECUTABLE}
        ARGS --grpc_out=${GENERATED_PROTO_HDR_DIR}
              --cpp_out=${GENERATED_PROTO_HDR_DIR}
              --plugin=protoc-gen-grpc=${GRPC_CPP_PLUGIN_EXECUTABLE}
              --proto_path=${PROTO_SRC_DIR}
              ${proto_file}
        DEPENDS ${proto_file} ${GRPC_CPP_PLUGIN_EXECUTABLE}
    )
endforeach()

foreachによりPROTO_SRCで定義したプロトファイル全てに対してコード生成を行うようにしています。


ここまでできたら、ビルドして下記のように実行して動作確認してみましょう。
クライアントサーバーよりリクエスト送信したデータが、サーバー側で受け取れていることが確認できます。

2.3. Debugging gRPC using Postman

https://learning.postman.com/docs/sending-requests/grpc/grpc-client-overview/

デバッグとして、上述のようにPostmanを使用する方法もあるので紹介します。

まずはPostmanのインストール。

terminal
sudo snap install postman

インストール後Postmanを起動し、localhost:50051を選択

Importをクリック

Invokeによりリクエスト送信します。

するとPostmanからgRPCサーバーへリクエストが送れることを確認できます。

3. ROS 2 and gRPC integration

ここからはROS 2とgRPCのインテグについて記載していきます。

3.1. gRPC Diagram

まずはgRPCとROS 2の仕様検討をしていきます。

今回やりたいこととして下記のソフトウェア要求とアーキテクチャ要求を満たすことを考えます。

SW要求項目 詳細
gRPC Client → Server通信 - データ取得リクエストを送信し、結果を受け取ること。
- 取得データをクライアント側で処理可能なこと。
gRPC Server → Client通信 - サーバーが処理結果をクライアントに返却すること。
ROS 2 Subscribe機能 - gRPC ServerがROS 2トピックをSubscribeし、データを受信すること。
ROS 2 Publisher機能 - gRPC Serverが受け取ったデータをROS 2トピックにPublishすること。
Arch要求項目 詳細
gRPCとROS 2間の連携 - gRPC Serverが通信の橋渡し役を担うこと。
運用監視とデバッグの容易さ - 各通信段階でのログを記録する仕組みを構築すること。

これをポンチ絵的に表すなら、下記で

  • gPRC get Client → gRPC Server ROS 2 Subscribe → gRPC get Client

  • gRPC set Client → gRPC Server ROS 2 Publisher → gRPC set Client

ダイアグラムで示すとこのようなイメージで要約すれば

  • ROS 2 PublishされたデータをgRPCサーバーで受けて、gRPC Client側で取得データを確認する
  • gRPCでセット&送信したデータは、ROS 2でPublishされる

が実装したい内容です。

3.2. gRPC Sequence

続いて、ソフトウェアシーケンス図の詳細設計を行います。

先程起こした要求からシーケンス図にします。

  • ROS 2 PublishされたデータをgRPCサーバーで受けて、gRPC Client側で取得データを確認する

この設計をシーケンス図に起こすとイメージは以下になります。

Get Client Sequence

  • gRPCでセット&送信したデータは、ROS 2でPublishされる

この設計をシーケンス図に起こすとイメージは以下になります。

Set Client Sequence

3.3. Coding ROS 2 and gRPC

3.1、3.2をベースにコーディングしていきます。

3.3.1. Coding proto file

まずは.protoファイルから。

robot_service.proto
syntax = "proto3";

package robot_service;

// ========== Import Protobuf ==========
import "std_msgs.proto";
import "nav_msgs.proto";

// ========== Request Message ==========
message Float32Request {
  Float32 float_data = 1;
}

message PoseRequest {
  Pose pose = 1;
}

// ========== Response Message ==========
message Float32Response {
  Float32 float_data = 1;
}

message PoseResponse {
    Pose pose = 1;
}

// ========== Service Definitions ==========
service RobotService {
  rpc GetFloat32(Float32Request) returns (Float32Response);
  rpc SetFloat32(Float32Request) returns (Float32Response);
  rpc SetPose(PoseRequest) returns (PoseResponse);
}

サービス定義(Service Definitions)でSet Request, Get Request用のサービスを宣言し、メッセージとしてFloat32Request, Float32Responseを定義しておきます。

3.3.2. Coding clinet file

続いて、client用のファイルを記述します。
例ではSet RequestをWebアプリからGUI操作により実現したいのでPython Flaskを使用しています。

grpc_client.py
from flask import Flask, render_template, request, jsonify
import grpc
import robot_service_pb2
import robot_service_pb2_grpc

app = Flask(__name__)

class GrpcClient:
    def __init__(self, server_address='localhost:50051'):
        self.channel = grpc.insecure_channel(server_address)
        self.stub = robot_service_pb2_grpc.RobotServiceStub(self.channel)  # Use the correct reference

    def get_float32(self):
        request = robot_service_pb2.Float32Request()
        response = self.stub.GetFloat32(request)
        return response.float_data.data

    def set_float32(self, value):
        request = robot_service_pb2.Float32Request()
        request.float_data.data = value
        response = self.stub.SetFloat32(request)
        return response.float_data.data

@app.route('/')
def index():
    return render_template('index.html')

@app.route('/get_float32', methods=['GET'])
def get_float32():
    grpc_client = GrpcClient()
    try:
        value = grpc_client.get_float32()
        return jsonify({'success': True, 'value': value})
    except Exception as e:
        return jsonify({'success': False, 'error': str(e)})

@app.route('/set_float32', methods=['POST'])
def set_float32():
    grpc_client = GrpcClient()
    try:
        value = float(request.json.get('value', 0))
        updated_value = grpc_client.set_float32(value)
        return jsonify({'success': True, 'updated_value': updated_value})
    except Exception as e:
        return jsonify({'success': False, 'error': str(e)})

if __name__ == '__main__':
    app.run(host='0.0.0.0', port=8080, debug=True)

class GrpcClientで、Set, Get用のスタブを定義し、GetはRequest下内用をそのまま返すように、Setは引数valueの値をRequestするようにスタブを定義します。

定義したスタブはGET/POSTメソッドを受け取ると、値をRequestするように@app.route下で宣言します。

3.3.3. Coding server file

最後にserverファイルを作成します。

float32_server.cpp
// ヘッダーインクルード略

class Float32ServiceImpl final : public robot_service::RobotService::Service {
public:
    /******************************************************************************
     * @fn      Float32ServiceImpl
     * @brief   Constructor that initializes ROS 2 publisher and subscriber
     * @param   node : A shared pointer to the ROS 2 node
     ******************************************************************************/
    explicit Float32ServiceImpl(std::shared_ptr<rclcpp::Node> node)
        : node_(node), get_float32_data(0.0) {
        // ROS 2 Publisher
        publisher_ = node_->create_publisher<std_msgs::msg::Float32>("/float32_topic", 10);
        publish_thread_ = std::thread(&Float32ServiceImpl::publishLoop, this);
        // ROS 2 Subscriber
        subscriber_ = node_->create_subscription<std_msgs::msg::Float32>(
            "/data", 10, std::bind(&Float32ServiceImpl::float32Callback, this, std::placeholders::_1));
    }

    grpc::Status GetFloat32(
      grpc::ServerContext* context,
      const robot_service::Float32Request* request,
      robot_service::Float32Response* response
    ) override {
        // Set the response with the current float32 data
        response->mutable_float_data()->set_data(get_float32_data);

        return grpc::Status::OK;
    }

    grpc::Status SetFloat32(
      grpc::ServerContext* context,
      const robot_service::Float32Request* request,
      robot_service::Float32Response* response) override {

        // Extract the float32 data from request
        float new_data = request->float_data().data();

        // Set the response with the updated new_data
        response->mutable_float_data()->set_data(new_data);

        // Update float 32 data
        set_float32_data = new_data;

        return grpc::Status::OK;
    }

// 以下略

まずはFloat32ServiceImplのコンストラクタでROS 2用のPub/Subを定義します。

続いて、.protoファイルでサービス定義(Service Definitions)したSetFloat32, GetFloat32を定義します。

今回はSet, Getで扱うデータが可変変数なのでmutable_float_data()というProtocol Buffers (Protobuf) によって生成されたクラスのメソッドを使用しています。

あとはお馴染み通り、ROS 2用のpublishLoop()float32Callbackを定義し、サーバービルドと実行の記述をします。(GitHub参照)

3.4. Run ROS 2 and gRPC Software

最後に動作確認して仕様通りの動きかを確認してみます。(GithubのREADME.mdの手順参照)

Get Request用のダミーROS 2 Publishデータの送信。

terminal
cd ~/dev_ws && . install/setup.bash
ros2 topic pub -r 1 /data std_msgs/msg/Float32 "{data: 5.0}"

ROS 2 Nodeブリッジ兼gRPC Serverを起動。

terminal
cd ~/dev_ws && . install/setup.bash
ros2 run ros2_grpc_server float32_server

クライアントFlask Webアプリの起動。

terminal
cd ~/dev_ws/src/ros2_grpc_server/script && python3 grpc_client.py

https://twitter.com/tasada038/status/1842940094652842294

上述のように

  • gRPCによってSet RequestしたデータがServer側とRviz2側で受信できていること
  • ROS 2 Publisherした値がgRPC側 Webアプリで受信できていること

が確認できたので、設計から実装まで無事終了となります。

Pythonコードが入っていると、.protoファイルの自動生成も一癖あったので、こちらはGithubソースを参照してください。


以上、ROS 2とgRPCのインテグでした。
Likeいただけると大変励みになりますので、よろしくお願いいたします。

Referecne

Qiita:gRPCのインストール

Zenn:Postman でgRPC のリクエスト送信してみる

Discussion