ROS2 for Unityで始めるUnityとROS2間の高速データ通信
はじめに
こんにちは、ROS2で自律航行システム等を開発している片岡というものです。
競技で使う船は軽自動車くらいのサイズがあって試験場に持っていくだけで1日仕事、ということでシミュレータで日常の開発タスクや画像認識アルゴリズムの学習を行っていくことが非常に重要となります。
今回ros2-for-unityというネイティブでUnityとROS2を通信させるライブラリが公開されたのでそれの使い方を備忘録としてまとめておこうと思います。
今回は開発環境として以下の環境で動作を確認しました。
ubuntu: 20.04
Unity: 2021.1.18f1
ROS2: Foxy
なぜros2-for-unityを使いたいのか
過去にUnityとROS/ROS2をつなぐライブラリの実装例は以下のようなものがありました。
ros-sharp
一番有名所のライブラリになります。
websocket上でjson文字列による通信を行うため非常に大きな通信遅延とROSへのデータ変換の遅延が入ります。
画像、点群データを何個からも送ると数10ms~数100msの遅延が発生しトピックレートが大きく低下します。
最初の導入やWindowsでROS1と通信するアプリケーション作成には良いがヘビーユーズには適さないと言えます。
Unity-Robotics-Hub
Unity公式から発表されたライブラリです。
ROS1/ROS2と通信することができます。
プロトコルは独自ですがTCPベースということなので様々なプラットフォームで運用することが可能になるでしょう。
ただ、TCPでデータを送ってROS1/ROS2のデータ構造に変換するステップが入るのでそこに遅延が発生しますし、Server Endpointに一旦処理を集約するためそこが処理のボトルネックになる可能性が高いです。
ロボットのUIを作ったり、ロボットと連携して動くスマホアプリを作ったりするには適切なアーキテクチャだと思いますが、シミュレータとしてUnity環境を使うにはどうしても削れる遅延は削らなくてはなりません。
そのため採用の選択肢からは外れてしまいます。
ros2-for-unity
ros2-for-unityはRobotec.aiによって開発されたUnityとROS2間の通信を行うライブラリです。
ROS2 C#クライアントライブラリをネイティブライブラリとしてUnity Projectに取り込み、DDSのプロトコルで他のROS2アプリケーションと通信します。
OSはWindowsとUbuntuをサポートしています。
無駄な変換が一切挟まっていないため、これより早いプロセス間通信の方法は存在しないと言えます。
以上の理由からパフォーマンスを最優先として考えros2-for-unityをお試ししてみました。
ros2-for-unityのビルド
こちらはチュートリアルの通りにやればうまく行きました。
この通りにやるだけで以下に示す基本的なデータ型はあらかたビルドされていました。actionlib_msgs
action_msgs
builtin_interfaces
diagnostic_msgs
geometry_msgs
lifecycle_msgs
nav_msgs
rcl_interfaces
ros2cs_common.dll.meta
ros2cs_core.dll.meta
rosgraph_msgs
sensor_msgs
shape_msgs
statistics_msgs
std_msgs
stereo_msgs
test_msgs
tf2_msgs
trajectory_msgs
unique_identifier_msgs
visualization_msgs
追加で欲しい場合はvcsに追記してビルドすれば良さそうです。
TalkerExampleでROS2 topicをpubする
公式のサンプルに日本語でコメントを追加しておきました。
// Copyright 2019-2021 Robotec.ai.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
using UnityEngine;
namespace ROS2
{
/// <summary>
/// An example class provided for testing of basic ROS2 communication
/// </summary>
[RequireComponent(typeof(ROS2UnityComponent))] // ここでExecutor等が含まれるUnityコンポーネントが同じ階層にいる必要があるのを明示
public class ROS2TalkerExample : MonoBehaviour
{
// Start is called before the first frame update
private ROS2UnityComponent ros2Unity;
private ROS2Node ros2Node;
private IPublisher<std_msgs.msg.String> chatter_pub;
private int i;
void Start()
{
ros2Unity = GetComponent<ROS2UnityComponent>(); // ここでExecutor等が含まれるUnityコンポーネントを読み込む
}
void Update()
{
if (ros2Unity.Ok())
{
if (ros2Node == null)
{
ros2Node = ros2Unity.CreateNode("ROS2UnityTalkerNode"); // ここでノードの名前を指定
chatter_pub = ros2Node.CreatePublisher<std_msgs.msg.String>("chatter"); // ここでノードのトピックを指定
}
i++;
std_msgs.msg.String msg = new std_msgs.msg.String();
msg.Data = "Unity ROS2 sending: hello " + i;
chatter_pub.Publish(msg); // データをPublish
}
}
}
} // namespace ROS2
このスクリプトを実行する前に、ROS2UnityComponentが以下の画像のようにインスペクター上で表示されていることを確認してください
Sensorを作ってデータをPublishする
Unityの中にセンサーを作ってデータを取り出そうとする場合、どのセンサもほぼ定型的な処理を行うことになります。(計測フレームの判定、データ発行フレームの判定、タイムスタンプのセット、etc..)
そういった処理をまとめ上げたSensor型がros2-for-unityライブラリには含まれており、それを使用して手短にコードを書くことができます。
以下のセンサはPoseStampedを一定のレートで吐き出すセンサーのサンプルです。
using System.Collections;
using System.Collections.Generic;
using UnityEngine;
using ROS2;
using geometry_msgs;
namespace ROS2ForUnityTest
{
[RequireComponent(typeof(ROS2UnityComponent))] // ここでExecutor等が含まれるUnityコンポーネントが同じ階層にいる必要があるのを明示
public class PoseSensor : ROS2.Sensor<geometry_msgs.msg.PoseStamped>
{
void Start()
{
ros2Unity = GetComponent<ROS2UnityComponent>(); // ここでExecutor等が含まれるUnityコンポーネントを読み込む
}
protected override bool HasNewData() { return true; } // データ更新があればtrueを返す関数
protected override geometry_msgs.msg.PoseStamped AcquireValue() // 最新のセンサ値を返す関数
{
pose_ = new geometry_msgs.msg.PoseStamped();
return pose_;
}
protected override void OnUpdate() // Update() 処理で呼ばれる関数
{
if (ros2Node == null)
{
ros2Node = ros2Unity.CreateNode("PoseSensor");
CreateROSParticipants(ros2Unity, ros2Node, "/test");
}
}
private geometry_msgs.msg.PoseStamped pose_;
private ROS2UnityComponent ros2Unity;
private ROS2Node ros2Node;
}
} // namespace ROS2ForUnityTest
このスクリプトを実行する前に、ROS2UnityComponentが以下の画像のようにインスペクター上で表示されていることを確認してください
動作確認
Unity-Editor
Unity-Editor上で動作確認をするには、Unity Editor上の再生ボタンをクリックします。
ros2 topic echoするとデータがUnityの世界から発行されているのが確認できます。
ビルドして動作確認
File -> Build and Runを選択してバイナリをビルド、実行する。
上の画像のようにUnityの世界からデータが発行されているのが確認できます。
以下のリンクからビルドしたバイナリがダウンロードできるようにしておきました。
Ubuntu 20.04、Foxy環境で動作を確認しています。
お試しください。
Discussion