今回はMetaQuest3のMR機能とROS2を組み合わせて遊んでみることにします。といってもQuest3は実質的にAndroidみたいなものなので,ROS2との連携方法については以前作ったスマホコントローラの時と全く同じだったりします。なので今回のメインはMRの部分ですかね。
環境
- Windows11(Unity用)
- Ubuntu22.04(ROS2用)
- ROS2 Humble
- Unity 2022.3.11f1
開発環境の構築
Meta Quest Developer Hub
こちらのページのDownload for Windows
からMeta Quest Developer Hubをダウンロードし,インストールしてください。
開発者設定
こちらのページからアカウントの認証を行い,新しい組織を作成します。分からないことがあれば公式チュートリアルを参照してください。
開発者アカウントを作れたら,次にQuest3を開発者モードにします。
スマートフォンのMeta Questアプリを開いて,
Menu
>デバイス
>Meta Quest 3
>ヘッドセットの設定
>開発者モード
と進んで,開発者モードをオンにします。
そのままQuest3とPCを有線接続すると,画面にUSBデバッグを許可しますか
と表示されるので,許可or常に許可を選びます。
Meta Quest Link
公式記事を参考にしてQuest3でQuest Linkを使えるようにしてください。
PCのOculusアプリを立ち上げて,設定
>ベータ
から開発者ランタイム機能
をオンにします。すると,その下に追加項目が表示されるので,Oculus Link経由でのパススルー
もオンにします。
Unity
-
プロジェクトの作成
Unity Hubを開いてプロジェクトを作成していきます。
プロジェクト
>新しいプロジェクト
>3D(URP)
と進んで,プロジェクト名と保存場所を設定したらプロジェクトを作成
を選択します。
-
Oculus統合SDKの導入
アセットストアからOculus Integration SDKを導入します。
マイアセットに追加
>Unityで開く
と選択すると,Unityで下の画面が開くのでインポート
をクリックします。
途中でポップアップが出てきても,基本的にはデフォルトの値を選んでおけば問題ありません。
再起動をしたらOculus統合SDKの導入は完了です。
-
プロジェクト設定
編集
>プロジェクト設定...
からProject Setting画面を開きます。-
プレイヤー
一番上の企業名
を適当なものに変更します。
Androidタブのその他の設定
>識別
,設定
の部分を下の画像のように変更します。
-
XR Pulug-in Management > Oculus
AndroidタブのQuest 3にチェックを入れておきます。
そもそもOculusタブがないという人は,XR Plugin Managementをインストールし,AndroidタブからOculusプラグインにチェックを入れてください。こちらの記事が参考になるかもしれません。
-
ビルドターゲットの変更
ファイル
>ビルド設定...
からBuild Setting
を開き,プラットフォームをAndroidに変更したらターゲットの切り替え
をクリックします。
最後にプロジェクトウィンドウからAsetts
>Setting
>URP-Balanced-Renderer
を選択して,インスペクターウィンドウでスクリーンスペースアンビエントオクルージョン
のチェックを外しておきます。
ROS2forUnity
ros2-for-unityのunitypackageを作成したのでこちらからダウンロードしてください。
プロジェクトウィンドウ上で右クリックをすると以下の画像のように表示が出てくるので,パッケージをインポート
>カスタムパッケージ...
をクリックします。
先ほどダウンロードしたフォルダの中にros2-for-unity-win-android.unitypackage
というファイルがあるので,それを選択しインポートします。
MRの設定
パススルー
MRをUnityで実現するには通常レイヤーに加えて,パススルーレイヤ―を追加しなければなりません。パススルーレイヤーは実行時にカメラから合成された映像に置き換えられます。
-
OVR Camera Rigの追加
ヒエラルキーウィンドウからDirectional Light
以外のオブジェクトを削除して,プロジェクトウィンドウからAssets
>Oculus
>VR
>Prefabs
>OVRCameraRig
をヒエラルキーウィンドウへ追加します。
-
OVR Camera Rigの設定
ヒエラルキーウィンドウでOVRCameraRig
を選択しインスペクターウィンドウを開きます。 -
Sky boxの無効化
ウィンドウ
>レンダリング
>ライティング
>環境
と進みます。
スカイボックスマテリアル
にNone
を設定し,環境ライティング
>ソース
を色
に,環境光の色
を黒にします。
ちなみにQuest Linkを有効にした状態でUnity上のPlay
を選択すると,わざわざapkファイルをインストールしなくてもQuest3でシーンを実行できます。もし実行されない場合は編集
>プロジェクト設定...
>Oculus
からProject Setup Toolを使ってAndroidとWindowsのエラーや警告を修正してからもう一度試してみてください。
シーンモデル
壁や床などの現実の物体を認識して,Unityで利用するにはシーンモデルという機能を用いる必要があります。シーンモデルとは現実の物体にシーンアンカーを紐づけたもので構成され,シーンアンカーは図形+意味を要素として持ちます。たとえば床のシーンアンカーには平面図形と,床という意味が紐づけられます。
また,シーンモデルにアクセスするにはOVRSceneManagerというUnityコンポーネントを利用します。
-
アンカーサポートの有効化
ヒエラルキーウィンドウでOVRCameraRig
を選択し,インスペクターウィンドウからOVRManager
>Quest Features
>Anchor Support
を有効にします。
-
OVRSceneManagerの追加と設定
- プロジェクトウィンドウから
Assets
>Oculus
>VR
>Prefabs
>OVRSceneManager
をヒエラルキーウィンドウに追加する。 -
Assets
>Oculus
>SampleFramework
>Usage
>SceneManager
>Prefabs
フォルダからInvisiblePlane
とInvisibleVolume
をOVRSceneManager
のインスペクターウィンドウのOVR Scene Manager
>Plane Prefab
とVolume Prefab
にそれぞれドラッグアンドドロップして割り当てる。
(OVR Scene Anchorスクリプトが割り当てられてあれば他のPrefabも割り当てられます。また,Prefab Overridesからシーンアンカーに紐づけられた意味毎に異なるPrefabを割り当てることもできるようです)
- プロジェクトウィンドウから
MRではこれら以外にも空間アンカーという重要な要素がありますが,今回は必要ないので説明しません。
https://developer.oculus.com/documentation/unity/unity-spatial-anchors-overview/
メイン実装
今回はテストとしてコントローラーのJoy Stickの値をPCに送り,同じ値をPCから受け取ってオブジェクトを動かしてみることにします。
最初にプロジェクトウィンドウのAsetts
下にScripts
というフォルダを作っておいてください。今後スクリプトはこのフォルダ内で作成します。
ROSの実装
- ROSControl.cs
プロジェクトウィンドウのScriptsフォルダ内で右クリックをして,作成
>C#スクリプト
と進んでスクリプトを作成します。ファイル名はROSControlとしています。
using ROS2;
using UnityEngine;
namespace MyROS
{
public class ROSControl : MonoBehaviour
{
internal static readonly ROSConfig Instance = new ROSConfig();
// Start is called before the first frame update
void Start()
{
TryGetComponent(out Instance.ros2Unity);
}
// Update is called once per frame
void Update()
{
if (Instance.ros2Unity.Ok())
{
if (Instance.ros2Node == null)
{
Instance.ros2Node = Instance.ros2Unity.CreateNode("unity_node");
Instance.joy_data_pub = Instance.ros2Node.CreatePublisher<geometry_msgs.msg.Twist>("joy_data");
Instance.cmd_vel_sub = Instance.ros2Node.CreateSubscription<geometry_msgs.msg.Twist>("cmd_vel", Instance.cmd_vel_cb);
}
}
}
}
class ROSConfig
{
public ROS2UnityComponent ros2Unity;
public ROS2Node ros2Node;
public IPublisher<geometry_msgs.msg.Twist> joy_data_pub;
public ISubscription<geometry_msgs.msg.Twist> cmd_vel_sub;
public geometry_msgs.msg.Twist cmd_vel_data;
public void cmd_vel_cb(geometry_msgs.msg.Twist msg)
{
cmd_vel_data = msg;
}
}
}
Twist型のjoy_dataというトピックをPCに送り,PCからは同じくTwist型のcmd_velを受け取ります。ROSConfigクラスでPublisherやSubscriberを設定し,ROSControlクラスでそのインスタンスを作成することで,他のファイルからもPublisherやPCから受け取った値を利用できるようにしています。
ヒエラルキーウィンドウで右クリックをして,空のオブジェクトを作成
からROSObject
という名前のオブジェクトを作成してください(名前は任意)。
そのオブジェクトに今作成したROSControl
スクリプトをドラッグアンドドロップでアタッチします。
さらにプロジェクトウィンドウからAssets
>Ros2ForUnity
>Scripts
>ROS2UnityComponent.cs
を探して,同じくROSObject
にアタッチしてください。
インスペクターウィンドウでこのようになっていれば正しくアタッチできています。
ROS_DOMAIN_IDの設定
- SetID.cs
こちらのファイルでROS_DOMAIN_IDを設定します。
using System;
using UnityEngine;
public class SetID : MonoBehaviour
{
void Start()
{
// ROS_DOMAIN_IDに123を設定する
Environment.SetEnvironmentVariable("ROS_DOMAIN_ID", "123");
// 上手く設定できているか確認する
string value = Environment.GetEnvironmentVariable("ROS_DOMAIN_ID");
Debug.Log("ROS_DOMAIN_ID:" + value + "\n");
}
}
例としてIDを123に設定しているので,各自変更してください。
このスクリプトもROSObject
にアタッチしておきます。
次にメニューから編集
>プロジェクト設定...
>スクリプト実行順序
と開き,右下の+からSetID
を追加してください。
SetID
の右側の欄に-1
と入力し,Apply
で適用します。こうすることでROS_DOMAIN_IDがROSよりも早く設定され,エラーを防ぐことができます。
オブジェクトの実装
ROSから送られてきた値を読み込んで動く物体を実装します。
今回は適当にヒエラルキーウィンドウにRobot
という名前の球を追加しました。
インスペクターウィンドウでコンポーネントを追加
からRigidbody
を追加しておきます。
- RobotControl.cs
using MyROS;
using System.Collections;
using System.Collections.Generic;
using UnityEngine;
public class RobotControl : MonoBehaviour
{
private Rigidbody robot;
// Start is called before the first frame update
void Start()
{
robot = GetComponent<Rigidbody>();
}
// Update is called once per frame
void Update()
{
//Unityはyが上
robot.AddForce((float)ROSControl.Instance.cmd_vel_data.Linear.X, 0.0f, (float)ROSControl.Instance.cmd_vel_data.Linear.Y);
}
}
ROSから受け取った値はコールバック関数内でcmd_vel_data
に格納されるので,その値をそのまま加速度としてRigitbodyに加えています。
スクリプトをRobot
にアタッチすると画像のようになると思います(サイズとマテリアルを調整しています)。
インスペクターウィンドウからプロジェクトウィンドウにRobot
をドラッグアンドドロップしてPrefab化したら,インスペクターウィンドウのRobot
は削除しておきましょう。
コントローラーの値を読む
コントローラーの値を読むにはシーンにOVR Manager
を配置する必要がありますが,これはOVRCameraRig
に既にアタッチされているので大丈夫です。
-
コントローラーの表示
まずはコントローラーのモデルを表示するためのPrefabを追加します。
Assets
>Oculus
>VR
>Prefabs
>OVRControllerPrefab
を,画像の通りにヒエラルキーウィンドウのLeftHandAnchor
とRightHandAnchor
の下に配置してください。
インスペクターウィンドウから,
LeftHandAnchor
下に配置した方はコントローラー
をL Touch
に,RightHandAnchor
下に配置した方はR Touch
に変更します。
-
GetInput.cs
GetInput
というスクリプトを作成し,コントローラーの値を読み取ります。
using System.Collections;
using System.Collections.Generic;
using UnityEngine;
using MyROS;
public class GetInput : MonoBehaviour
{
[SerializeField]
private GameObject robot; //インスペクターウィンドウからrobotオブジェクトを設定
private OVRInput.Controller controller;
private geometry_msgs.msg.Twist send_data;
// Start is called before the first frame update
void Start()
{
//コントローラーを取得
controller = GetComponent<OVRControllerHelper>().m_controller;
//Twistの初期化
send_data = new geometry_msgs.msg.Twist();
}
// Update is called once per frame
void Update()
{
//Button One = Aボタンが押された時の処理
if (OVRInput.GetDown(OVRInput.Button.One, controller))
{
//コントローラーの位置と方向に合わせてrobotを配置
Instantiate(robot, transform.position, transform.rotation);
}
//右のコントローラーのstickから値を読み込んでPublish
send_data.Linear.X = OVRInput.Get(OVRInput.Axis2D.SecondaryThumbstick).x;
send_data.Linear.Y = OVRInput.Get(OVRInput.Axis2D.SecondaryThumbstick).y;
ROSControl.Instance.joy_data_pub.Publish(send_data);
}
}
スクリプトをRightHandAnchor
下に配置したOVRControllerPrefab
にアタッチしてください。
インスペクターウィンドウからGet Input
>Robot
に,先ほど作成したRobot
のPrefabをドラッグアンドドロップにより割り当てます。
ビルド&インストール
以上でUnity側の実装は終わったので,ファイル
>ビルド設定...
>ビルド
からapkファイルとして出力します。
Meta Quest Developer Hub
を起動し,Quest3を接続した状態でapkファイルをファイルをウィンドウ上にドラッグアンドドロップすると,インストール先を聞かれるので,接続デバイスを選んでapkファイルをインストールします。
Device Manager
タブで下のように表示されていれば大丈夫です。
PC側の実装
こちらは特に説明することもないので,コードだけ置いておきます。
#include <chrono>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"
using namespace std::chrono_literals;
class MinimalPubSub : public rclcpp::Node{
public:
MinimalPubSub() : Node("minimal_pubsub"){
auto topic_callback = [this](const geometry_msgs::msg::Twist& msg) -> void{
auto message = geometry_msgs::msg::Twist();
message = msg;
std::cout << "X:" << message.linear.x << "\nY:" << message.linear.y << std::endl;
publisher_->publish(message);
};
rclcpp::QoS qos(rclcpp::KeepLast(10));
publisher_ = this->create_publisher<geometry_msgs::msg::Twist>("cmd_vel", qos);
subscription_ = this->create_subscription<geometry_msgs::msg::Twist>("joy_data", qos, topic_callback);
}
private:
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr publisher_;
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr subscription_;
};
int main(int argc, char* argv[]){
rclcpp::init(argc,argv);
rclcpp::spin(std::make_shared<MinimalPubSub>());
rclcpp::shutdown();
return 0;
}
テスト
PC側で先ほど作成したROS2ノードを立ち上げます。
Quest3を起動して,メニューバー右端のアプリライブラリ
からアプリを検索
と進んで,全て
と書かれたタブをクリックして提供元不明
を選択します。すると先ほどインストールしたアプリが出てくるので起動します。
Aボタンで球体出現,ジョイスティックで球体が動けばうまくいっています。PC上でもQuest3から値が送られてきていることが分かります。
※デバッグ用にコンソールを表示しています。
おわりに
想像以上にSDKや公式ドキュメントが充実しており,ほとんど詰まることなく実装できてしまいました。これからどんなものを作ろうかと,夢が広がります。
参考文献