Unity x ROS をこれから始める方へ、開発Tips書いてみた - aptpod Tech Blog

aptpod Tech Blog

株式会社アプトポッドのテクノロジーブログです

Unity x ROS をこれから始める方へ、開発Tips書いてみた

aptpod Advent Calendar 2024 12月11日の記事です。

ネイティブアプリケーション開発を担当している上野です。近年、デジタルツインの注目度が高まりつつある中、実際にデジタルツインアプリケーションを作る際の開発プラットフォームの選択肢として、UnityやROSが挙げられると思います。

aptpod,Inc News

上記ニュースで開発しているアプリケーションもUnityとROSが活用されています。

今回は実際に私がUnityとROSを利用してデジタルツインアプリケーションを開発している際に利用しているツールや取り扱い方法などをご紹介します。

UnityとROSの接続方法

UnityとROSとの接続は以下の2つのモジュールを利用しています。

ROS-TCP-Connector はUnity内にインストールするパッケージです。こちらを利用する事でTCP経由でROSメッセージのサブスクライブやパブリッシュが可能です。

ROS-TCP-Endpoint はROS用のパッケージでROSネットワーク内のメッセージをTCPでUnityへ橋渡してくれるエンドポイントです。

よくある例でROSBridgeを利用してWebSocket経由でROSメッセージのやり取りをする例がありますが、それらでやり取りするよりも圧倒的にパフォーマンスが良いようです。実際にPC内にDockerで作成したROSサーバーで発行した数百Mbpsクラスの点群データもスムーズにUnityに届けられているのでかなり高速と言えます。

ROSサーバーのセットアップ

今回はUnityがインストールされたWindowsPC内にDockerを利用してROS2サーバー(ノード)をセットアップし、ROSメッセージのやり取りを行えるようにします。

今回の構成

Docker Composeファイルの作成

Dockerのセットアップ方法は Unity-Robotics-Hub というROSとUnityのチュートリアルがあり、同一リポジトリ内の ros_unity_integration にROS-TCP-Endpointのパッケージを自動追加しつつROSサーバーをセットアップするDockerファイルがあるので利用すると簡単です。

私はros_unity_integrationフォルダと同階層にDocker Composeファイルを作成して利用しています。

ROSサーバーをDockerで建てる際のフォルダ例

  • docker-compose.yml
#version: "3"

services:
  ros2-endpoint:
    image: foxy
    container_name: ros2
    build:
      context: ./ros_unity_integration
      dockerfile: ./ros2_docker/Dockerfile
    ports:
      - 10000:10000
    volumes:
      - ./bagfiles:/home/dev_ws/bagfiles
    networks:
      - ros2_external
    restart: always
    command: >
      bash -c ". /home/dev_ws/install/setup.bash &&
      export FASTRTPS_DEFAULT_PROFILES_FILE=/home/dev_ws/src/fastrtps-profile.xml &&
      ros2 run ros_tcp_endpoint default_server_endpoint --ros-args -p ROS_IP:=0.0.0.0 -p ROS_TCP_PORT:=10000"

  ros2-endpoint2:
    image: foxy
    container_name: ros2_for_controller
    build:
      context: ./ros_unity_integration
      dockerfile: ./ros2_docker/Dockerfile
    ports:
      - 10001:10001
    volumes:
      - ./bagfiles:/home/dev_ws/bagfiles
    networks:
      - ros2_external
    restart: always
    command: >
      bash -c ". /home/dev_ws/install/setup.bash &&
      export FASTRTPS_DEFAULT_PROFILES_FILE=/home/dev_ws/src/fastrtps-profile.xml &&
      ros2 run ros_tcp_endpoint default_server_endpoint --ros-args -p ROS_IP:=0.0.0.0 -p ROS_TCP_PORT:=10001"

networks:
  ros2_external:

上記Docker Composeファイルでは、チュートリアル で行っているROS-TCP-Endpointのセットアップコマンドなどを一括実行させています。

また、Docker Composeファイルと同階層に作ったbagfilesフォルダをマウントする事で検証で利用するROSbagファイルを簡単に参照できるようにしています。

コンテナが複数ありますが、こちらはUnityアプリとROS-TCP-Endpointの疎通は1対1でないと接続不調になるケースがあった為です。 ROSは同一ネットワーク内のメッセージを自動で送受信する事が出来ます。Docker Composeの設定でコンテナ同士の通信を許可しておけば複数のコンテナに分かれていても問題はありません。 各コンテナの違いはコンテナ名とポートのみです。

私はコンテナが複数と1つだけのDocker Composeファイルを作成して使い分けています。

Dockerコンテナの起動

Dockerコンテナの起動コマンドは以下です。

# for docker-compose.yml
docker compose up -d

# for docker-compose2.yml
docker compose -f docker-compose2.yml up -d

対象のDocker Composeファイルのファイル名が docker-compose.yml 以外の場合は -f オプションでファイル名を指定します。

コンテナの停止例は以下です。

# for docker-compose.yml
docker compose down --rmi all --volumes --remove-orphans
or
docker compose -f docker-compose2.yml down --rmi all --volumes --remove-orphans

Docker自体のセットアップ方法は今回は解説しませんがWindowsの場合はWSL(Windows Subsystem for Linux)内、Macの場合はColimaを利用、Linuxの場合はOSへ直接セットアップして利用しています。

Unityアプリのセットアップ

プロジェクトの作成

執筆日(2024/12) ではUnityのプロジェクトを作成する際のプロジェクトテンプレートは ビルトインレンダーパイプライン を利用しています。

Unityプロジェクト作成時のビルトインレンダーパイプラインのテンプレート

ユニバーサルレンダーパイプラインでも開発できるかと思いますがiPadなどタブレット対応も考慮している点と、より処理を軽量化したいケースで従来のビルトインレンダーパイプラインの方が勝っているかなと現時点では感じています。

ROS-TCP-Connectorのセットアップ

ROS-TCP-Connectorのセットアップ方法はREADMEに書かれている通りでPackage Manager内でGitのURLからインポートする方法があるのでそちらからインストールしてください。

Package Managerで選択する項目

ただ、私がROS-TCP-Connectorを利用する場合は、送受信しているROSメッセージの伝送帯域を確認したいケースが多くあり、標準では伝送帯域を収集する機能を要していない為、フォークして少し調整した物を利用しています。

github.com

ROS-TCP-Connector インストール後の画面

帯域の測定方法に興味がある場合は テスト用のスクリプト がありますので参照ください。

ROSバージョンの選択

ROS-TCP-ConnectorはROS1とROS2の両方に対応しています。必要に応じて Robotics/ROS Settings よりバージョンの切り替えを行ってください。

ROS Settingsの表示方法

ROSバージョンは変更可能

ROSコネクションの配置

Unity内でGameObjectにROS Connectionコンポーネントを配置し、必要に応じてIPアドレスやポートを変更すればROSサーバーとの疎通に関しては準備完了です。

ROS Connection のInspector

うまくROSサーバーと接続できていればアプリ実行時にシーン画面の左上に表示される矢印が青く点灯します。

ROSとの接続が成功している際の表示

接続できていない場合は、矢印が赤色になります。

ROSとの接続に失敗している際の表示

ROSメッセージのサブスクライブ/パブリッシュ検証

ここからはデータの疎通確認の例を記載します。

ROSメッセージをサブスクライブしてみる

ROSメッセージをサブスクライブするには対象のメッセージのトピック名と型をROS Connectionに渡すだけで可能です。

  • ROS_StringSubscriber.cs
using RosMessageTypes.Std;
using System;
using Unity.Robotics.ROSTCPConnector;
using UnityEngine;
using UnityEngine.Events;

public class ROS_StringSubscriber : MonoBehaviour
{
    [SerializeField]
    private string topicName = "/string";

    public string ReceivedTime;

    public string Data;

    public bool ShowReceiveLog = true;

    public UnityEvent<string> OnReceiveData = new UnityEvent<string>();

    // Start is called before the first frame update
    void Start()
    {
        ROSConnection.GetOrCreateInstance().Subscribe<StringMsg>(this.topicName, (message) =>
        {
            if (!this.enabled) return;
            if (ShowReceiveLog) Debug.Log($"OnReceiveStringMessage(topicName: {this.topicName}, data: {message.data})");
            var dateTime = DateTime.UtcNow;
            ReceivedTime = dateTime.ToLocalTime().ToString("HH:mm:ss.ffffff");
            Data = message.data;
            OnReceiveData?.Invoke(message.data);
        });
    }
}

作成したコンポーネントをGameObjectに追加し、対象のトピック名を設定するだけで利用できます。

作成した ROS_StringSubscriber の Inspector

Unityのプロジェクトを実行したらROSサーバーからメッセージをパブリッシュしてみます。

# Launching Docker containers.
docker compose up -d

# Access to Docker containers.
docker exec -it ros2 /bin/bash

# Sending ROS messages.
ros2 topic pub --once /string std_msgs/msg/String "data: Hello World!"
or
ros2 topic pub --once /string std_msgs/String "data: Hello World!"

ROSメッセージを受信した際の ROS_StringSubscriber の Inspector

JSONなども送信可能です。

ros2 topic pub --once /string std_msgs/String "data: {'key': 'value'}"

JSON形式を受信した際の ROS_StringSubscriber の Inspector

ROSbagファイルに格納されたROSメッセージの確認方法

ROSbagに格納されたメッセージの確認を行う場合はまずは ros2 bag info で格納されているROSメッセージのTopic名や型を調べます。

ros2 bag info の実行例

上記で判明したTopic名と型を用いてUnityでサブスクライブ設定を行います。

ROSbag内のデータは時系列に格納されており、ros2 bag play を行う事で実際に記録した際と同じ時間間隔でメッセージの再生が可能です。

ros2 bag play {ROSbagファイルパス}

上記を実行する事で格納されたROSメッセージがROSネットワークに発信され、Unityにも同様にROSメッセージを伝達する事が可能になります。

ROSメッセージをパブリッシュしてみる

続いて逆にUnityからROSサーバーへデータを送信してみます。以下の2つのファイルを用意してみました。

  • ROS_StringPublisher.cs
using RosMessageTypes.Std;
using System.Collections;
using System.Collections.Generic;
using Unity.Robotics.ROSTCPConnector;
using UnityEngine;

public class ROS_StringPublisher : MonoBehaviour
{
    [SerializeField]
    private string topicName = "/string2";

    public bool ShowSendLog = true;

    private ROSConnection ros;

    private StringMsg msg;

    private bool enable = false;

    // Start is called before the first frame update
    void Start()
    {
        // Setup ROS
        this.ros = ROSConnection.GetOrCreateInstance();
        this.ros.RegisterPublisher<StringMsg>(this.topicName);

        // Setup ROS Message
        this.msg = new StringMsg();
    }

    public void Publish(string data)
    {
        if (!enable) return;
        if (ShowSendLog) Debug.Log($"PublishStringMessage(topicName: {this.topicName}, data: {data})");
        this.msg.data = data;
        this.ros.Publish(this.topicName, this.msg);
    }

    private void OnEnable()
    {
        enable = true;
    }

    private void OnDisable()
    {
        enable = false;
    }
}
  • PublishSample.cs
using UnityEngine;
using UnityEngine.Events;

public class PublishSample : MonoBehaviour
{
    public string Message = "Unity to ROS test";

    public UnityEvent<string> PublishEvent = new UnityEvent<string>();

    // Update is called once per frame
    void Update()
    {
        if (Input.GetKeyDown(KeyCode.Space))
        {
            PublishEvent?.Invoke(Message);
        }
    }
}

ROS_StringPublisherではROSConnectionに対し、送信するトピック名と型を登録し、関数Publish()に送られてきた文字列を送信する例になります。

PublishSampleはスペースキーが押されたら、変数Messageに格納されている文字列をPublisherに伝達できるようにイベントを発火しています。

新しくGameObjectを作成し、それぞれのコンポートを追加したら、PublishSampleのInspectorでPublishEventにROS_StringPublisherのPublish関数を登録します。

PublishSampleにROS_StringPublisherのROSメッセージ送信処理を登録する例

PublishSampleにROSメッセージ送信のイベントが登録できた際の例

Unityのプロジェクトを実行後、スペースキーを押すとログが出力されればOKです。

ROSメッセージ送信のイベントが発生した際に表示されるログ

実際にROSサーバー側で送信されたROSメッセージを確認するには ros2 topic echo を利用します。

# Access to Docker containers.
docker exec -it ros2 /bin/bash

# Checking ROS messages.
ros2 topic echo /string2 std_msgs/String

ROSサーバーでros topic echoを実行した際の例

正しくメッセージが受信できれば、型に定義されたデータ名とその中身が表示されます。

独自に設計されたROSメッセージの生成方法

標準でサポートされているROSメッセージだけでなく、状況に応じてカスタマイズされたROSメッセージを利用したいケースがあると思います。

ROS-TCP-ConnectorではROSメッセージの生成もサポートしているので対応可能です。

ROS Message Browserの開き方

Robotics/Generate ROS Messages... で ROS Message Browserを開き、パスの設定を行います。

ROS Messageの生成例

基本はUnityプロジェクト内のAssetsフォルダ配下に ROSMessages フォルダを作成し、ROSエンジニアから共有頂いたROSMessage定義ファイル( 拡張子 .msg )を格納すれば自動生成されます。

今回は NMEAメッセージをUnity用ROSMessageに変換してみました。

github.com

ROS用に設計されたロボットモデルのインポート

ROS用に設計されたロボットモデル多くはxacrourdfといったxml形式のモデルが多いです。これらのモデルはUnityでは標準サポートしていない為、Unityへインポートする例も紹介します。

TurtleBot3 Waffle Piモデル

今回はURDFで定義されたTurtleBot3モデルを利用します。

利用するリポジトリは以下です。

github.com

URDFのインポートには URDF-Importer というUnityパッケージを利用します。

github.com

ROS-TCP-Connectorの時と同じようにGithubのリンクからインポートを行います。

URDF-Importer のインストール後の画面

Assets配下にURDFフォルダを作成しその配下に TurtleBot3の プロジェクト をクローンしてきます。

URDFファイルのインポート方法

クローンしてきたプロジェクトのトップディレクトリにurdfファイルありますのでそちらを右クリックなどでオプションを表示し、 Import Robot from Selected URDF file 選択し、 URDF Import Settings を表示します。

URDF Import Settings

表示された URDF Import Settings で Import URDF を選択することでモデルが生成されると思います。

URDFから生成された3Dモデル例

今回用意したurdfのリポジトリは元のリポジトリからフォークして若干調整しています。

  • turtlebot3_waffle_pi.urdf
...
  <link name="base_link">
    <visual>
      <origin xyz="-0.064 0 0.0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://turtlebot3_description/meshes/bases/waffle_pi_base.stl" scale="0.001 0.001 0.001"/>
      </geometry>
      <material name="light_black"/>
    </visual>
...

urdfファイルの中身を見るとmeshタグにpackageの定義がされていますが、執筆時点では URDF-Importer はpackageの解決が出来ない為、そのまま利用するとエラーになっていました。

URDFの変換エラー

packageのトップディレクトリはurdfファイルがある階層と同じ位置から始まる為、修正した内容としてはurdfファイルをリポジトリのトップへ移動して対応しました。

一旦これらで可視化まで出来ましたが、実はこのままだと生成されたモデルに重力が適用されていてアプリケーションを実行するとモデルが自由落下してしまいます。

自由落下中のモデル

デジタルツインの様なアプリ開発のケースではROS空間で動作しているROSモデルをそのままの座標で可視化することが目的な為、重力といったシミュレーション要素は不要のため、デフォルトで生成された不要なコンポーネントは削除して利用しています。

削除するスクリプト例は以下です。

  • Editor/RemoveURDFImporterComponents.cs
using UnityEngine;
using UnityEditor;

#if UNITY_EDITOR

using Unity.Robotics.UrdfImporter;
using Unity.Robotics.UrdfImporter.Control;

public class RemoveURDFImporterComponents : MonoBehaviour
{
    [MenuItem("GameObject/Remove URDF-Importer Components", false, 0)]

    static void Execute(MenuCommand command)
    {
        foreach (GameObject obj in Selection.gameObjects)
        {
            RemoveChildComponents(obj.transform);
        }
    }

    private static void RemoveChildComponents(Transform t)
    {
        for (int i = 0; i < t.childCount; i++)
        {
            var child = t.GetChild(i);
            RemoveComponents(child);
            RemoveChildComponents(child);
        }
        RemoveComponents(t);
    }

    private static void RemoveComponents(Transform t)
    {
        // RemoveComponent<>(t);
        RemoveComponent<UrdfRobot>(t);
        RemoveComponent<Controller>(t);
        RemoveComponent<UrdfPlugins>(t);
        RemoveComponent<UrdfPlugin>(t);
        RemoveComponent<UrdfLink>(t);
        RemoveComponent<UrdfVisuals>(t);
        RemoveComponent<UrdfVisual>(t);
        RemoveComponent<UrdfCollisions>(t);
        RemoveComponent<UrdfCollision>(t);
        RemoveComponent<UrdfLink>(t);
        RemoveComponent<UrdfInertial>(t);
        RemoveComponent<UrdfJointFixed>(t);
        RemoveComponent<UrdfJointRevolute>(t);
        RemoveComponent<UrdfJointPrismatic>(t);
        RemoveComponent<UrdfJointContinuous>(t);

        // Must be last...
        RemoveComponent<ArticulationBody>(t);
    }

    private static void RemoveComponent<T>(Transform t) where T : Object
    {
        var s = t.GetComponent<T>();
        while (s != null)
        {
            DestroyImmediate(s);
            s = t.GetComponent<T>();
        }
    }
}

#endif

上記はAssetsフォルダ配下に Editor フォルダを作成してその中に作成します。

URDF-Importer の不要な項目を削除する

あとは Hierachy内のURDF-Importerから生成されたモデルを右クリック等でオプションを表示し、新たに追加された Remove URDF-Importer Components を実行する事で不要な項目が削除されます。

Remove URDF-Importer Components 実行後

あとはROSメッセージのTFなどからロボットの位置や関節情報をUnityのモデルにバインドしてあげると同期が成立すると思います。

TFのサブスクライブ例は以下です。

  • ROS_TFSubscriber
using RosMessageTypes.Geometry;
using RosMessageTypes.Tf2;
using System;
using System.Collections.Generic;
using Unity.Robotics.ROSTCPConnector;
using Unity.Robotics.ROSTCPConnector.ROSGeometry;
using UnityEngine;
using UnityEngine.Events;

public class ROS_TFSubscriber : MonoBehaviour
{
    [SerializeField]
    private string topicName = "/tf";

    [Serializable]
    public class TFFrame : IEquatable<TFFrame>
    {
        public string ChildFrameId;
        public string FrameId;

        public string ReceivedTime;

        public bool DisablePosition = false;
        public Vector3 Position;

        public bool DisableRotation = false;
        public Quaternion Rotation;

        public bool ShowReceiveLog = true;

        public UnityEvent<Vector3, Quaternion> OnReceiveTransform = new UnityEvent<Vector3, Quaternion>();
        public UnityEvent<Vector3> OnUpdatePosition = new UnityEvent<Vector3>();
        public UnityEvent<Quaternion> OnUpdateRotation = new UnityEvent<Quaternion>();

        public void OnReceiveMessage(TransformMsg message)
        {
            if (!this.Script.enabled) return;
            if (ShowReceiveLog) Debug.Log($"OnReceiveTFMessage(childFrameId: {ChildFrameId}, frameId: {FrameId}, data: {message})");
            var dateTime = DateTime.UtcNow;
            ReceivedTime = dateTime.ToLocalTime().ToString("HH:mm:ss.ffffff");
            if (!DisablePosition) Position = message.translation.From<FLU>();
            if (!DisableRotation) Rotation = message.rotation.From<FLU>();
            OnUpdatePosition?.Invoke(Position);
            OnUpdateRotation?.Invoke(Rotation);
            OnReceiveTransform?.Invoke(Position, Rotation);
        }

        internal MonoBehaviour Script;

        public bool Setup(MonoBehaviour Script)
        {
            // Load settings.
            if (string.IsNullOrEmpty(this.ChildFrameId) && string.IsNullOrEmpty(this.FrameId)) return false;
            this.Script = Script;
            return true;
        }

        public static bool operator ==(TFFrame l, TFFrame r) => l.Equals(r);
        public static bool operator !=(TFFrame l, TFFrame r) => !(l == r);

        public bool Equals(TFFrame other)
        {
            if (ReferenceEquals(other, null)) { return false; }
            if (this.ChildFrameId != other.ChildFrameId) { return false; }
            if (this.FrameId != other.FrameId) { return false; }
            return true;
        }

        public override int GetHashCode()
        {
            int hash = 1;
            if (!string.IsNullOrEmpty(ChildFrameId)) hash ^= ChildFrameId.GetHashCode();
            if (!string.IsNullOrEmpty(FrameId)) hash ^= FrameId.GetHashCode();
            return hash;
        }

        public override bool Equals(object obj)
        {
            if (obj is TFFrame v)
            {
                return Equals(v);
            }
            return false;
        }
    }

    [SerializeField]
    private List<TFFrame> dataList = new List<TFFrame>();

    // Start is called before the first frame update
    void Start()
    {
        var deleteList = new List<TFFrame>();
        foreach (var data in this.dataList)
        {
            if (!data.Setup(this))
            {
                deleteList.Add(data);
            }
        }
        foreach (var data in deleteList)
        {
            this.dataList.Remove(data);
        }
        if (this.dataList.Count == 0)
        {
            Debug.Log($"{topicName} list is empty, so the subcrite is skipped.");
            this.gameObject.SetActive(false);
            return;
        }
        ROSConnection.GetOrCreateInstance().Subscribe<TFMessageMsg>(this.topicName, (message) =>
        {
            foreach (var t in message.transforms)
            {
                foreach (var frame in dataList)
                {
                    if (t.child_frame_id.Equals(frame.ChildFrameId))
                    {
                        if (!string.IsNullOrEmpty(frame.FrameId) && !t.header.frame_id.Equals(frame.FrameId))
                        {
                            continue;
                        }
                        frame.OnReceiveMessage(t.transform);
                    }
                }
            }
        });
    }
}

ROS_TFSubscriberとモデルとのバインド例

その他、開発する上で注意ポイント

Windowsの場合、Dockerで作成したROSサーバーは同一LAN内のROSノード(サーバー)とは接続できない

上記の通り開発や検証端末でWindowsを選択する場合は注意が必要です。設定によってはローカルホスト外と通信できる可能性もありますが恐らく簡単ではないと思います。 LinuxでUnityアプリを動かし、DockerでROSサーバーを建てた場合はこの課題は発生しないので場合によっては動作端末にLinuxを選ばなければならないケースもあるかもしれません。

UnityとROSでは座標系が違う

ROSメッセージのTFなどでロボットの座標をUnity内のモデルにそのまま適用すると関節があらぬ方向へいったりします。

  • ROS: 右手系
  • Unity: 左手系

それぞれの座標系は上記の通りでして、一応ROS-TCP-Connector内でそれらの変換もサポートしているので利用すると良いと思います。

// Convert from ROS to Unity
var unity = message.translation.From<FLU>();
// Convert from Unity to ROS
var ros = FLU.ConvertFromRUF(unity);

最後に

いかがでしたでしょうか? Unity Technologiesで用意されているモジュールがとても優秀な為、ROSとの通信自体はかなり簡単に行えます。 今回はROSとUnityのみの解説となりましたが、ROSConnectionで行っているお作法は私が開発を担当している intdash-unity に簡単に置き換える事が可能です。

tech.aptpod.co.jp

intdash では現存するROSサーバーと併用して、簡単にインターネットを超えてROSメッセージを伝送する事も可能なのでROSプラットフォームとしての可能性が広がると思います。

IoTデータを利用したプラットフォーム、IoTサービスの開発や、リアルタイムデジタルツイン、製造現場のDX化など、IoTシステムの開発でお困りのことがあれば、ぜひ弊社までお声がけください。

弊社の問い合わせフォームはこちらです。

www.aptpod.co.jp