見出し画像

ROS入門 (18) - ROS-Unity間のサービスによる通信

「ROS-TCP-Connector」と「ROS-TCP-Endpoint」によるROS-Unity間のサービスによる通信の手順をまとめました。

・Melodic
・Unity 2020.3
・ROS-TCP-Connector 0.6.0
・ROS-TCP-Endpoint 0.5.0

ROS入門 (12) - ROS1のサービスによる通信」で作成したhelloパッケージの「client」「server」とUnityのメッセージの送受信を行います。

前回

1. ROS側の準備

ROS側の準備手順は、次のとおりです。

(1) ポート番号「10000」「5005」を追加して、Dockerイメージを起動。
UnityとROSの間の通信は、ポート番号「10000」「5005」が必要です。Unityにサービスファイルをインポートするため、フォルダのマウントも行っています。

$ docker run -p 6080:80 -p 10000:10000 -p 5005:5005 --shm-size=1024m tiryoh/ros-desktop-vnc:melodic

(2) 「helloパッケージ」の準備。
ROS入門 (12) - ROS1のサービスによる通信」と同様です。

(3) 「ROS-TCP-Endpoint」パッケージのインストール。

$ cd ~/catkin_ws/src
$ git clone https://github.com/Unity-Technologies/ROS-TCP-Endpoint
$ cd ..
$ catkin build
$ source ~/catkin_ws/devel/setup.bash

3. Unity側の準備

Unity側の準備手順は、次のとおりです。

(1) ROS-TCP-Connectorのインストール。
ROS入門 (16) - ROS-Unity間通信」と同様です。

(2) ROSの設定の確認。
ROS入門 (16) - ROS-Unity間通信」と同様です。

(3) サービスファイルのインポート。
ROS入門 (16) - ROS-Unity間通信」の手順で「AddTwoInts.srv」をインポートします。

画像1

(4) サーバーの実装。
(1) Hierarchyウィンドウの「+ → Create Empty」で空のGameObjectを作成し、「AddTwoIntsServer」と名前を指定し、新規スクリプト「AddTwoIntsServer」を追加し、以下のように編集。

using UnityEngine;
using Unity.Robotics.ROSTCPConnector;
using Unity.Robotics.ROSTCPConnector.ROSGeometry;
using AddTwoIntsRequest = RosMessageTypes.Hello.AddTwoIntsRequest;
using AddTwoIntsResponse = RosMessageTypes.Hello.AddTwoIntsResponse;

public class AddTwoIntsServer : MonoBehaviour
{
    void Start()
    {
        // ROSコネクションへのサービスの登録
        ROSConnection.GetOrCreateInstance().ImplementService<
            AddTwoIntsRequest, AddTwoIntsResponse>("add_two_ints", AddTwoIntsCallback);
    }

    private AddTwoIntsResponse AddTwoIntsCallback(AddTwoIntsRequest request)
    {
        AddTwoIntsResponse response = new AddTwoIntsResponse();
        response.sum = request.a + request.b;
        return response;
    }
}

(5) クライアントの実装。
(1) Hierarchyウィンドウの「+ → Create Empty」で空のGameObjectを作成し、「AddTwoIntsClient」と名前を指定し、新規スクリプト「AddTwoIntsClient」を追加し、以下のように編集。

using UnityEngine;
using Unity.Robotics.ROSTCPConnector;
using AddTwoIntsRequest = RosMessageTypes.Hello.AddTwoIntsRequest;
using AddTwoIntsResponse = RosMessageTypes.Hello.AddTwoIntsResponse;

public class AddTwoIntsClient : MonoBehaviour
{
    ROSConnection ros;

    void Start()
    {
        // ROSコネクションへのサービスの登録
        ros = ROSConnection.GetOrCreateInstance();
        ros.RegisterRosService<AddTwoIntsRequest, AddTwoIntsResponse>("add_two_ints");

        // リクエストの生成
        AddTwoIntsRequest request = new AddTwoIntsRequest(1, 2);

        // リクエストの送信
        ros.SendServiceMessage<AddTwoIntsResponse>("add_two_ints", request, AddTwoIntsCallback);
    }

    void AddTwoIntsCallback(AddTwoIntsResponse response)
    {
        print("1 + 2 = " + response.sum);
    }
}

4. 実行

実行手順は、次のとおりです。

◎ ROS側の実行
(1) ターミナルを開き、「roscore」を実行。

$ roscore

(2) もう1つのターミナルを開き、ROSのIPとポートを指定して、「ROS-TCP-Endpoint」を実行。

$ rosparam set ROS_IP 0.0.0.0
$ rosparam set ROS_TCP_PORT 10000
$ rosrun ros_tcp_endpoint default_server_endpoint.py

◎ ROSのクライアントからUnityのサーバーへのアクセス
(1) Unityの「AddTwoIntsServer」をアクティブ、「AddTwoIntsClient」を非アクティブにして、Playボタンで実行。

(2) ROSで、もう1つのターミナルを開き、「client」を実行。

$ rosrun hello client.py

◎ UnityのクライアントからROSのサーバーへのアクセス
(1) ROSで、もう1つのターミナルを開き、「server」を実行。

$ rosrun hello server.py

(2) Unityの「AddTwoIntsServer」を非アクティブ、「AddTwoIntsClient」をアクティブにして、Playボタンで実行。
コンソールに出力されます。

1 + 2 = 3

5. 参考

次回



この記事が気に入ったらサポートをしてみませんか?