デモ
こちらが完成イメージです。
(音楽入れ忘れたので心のDJによる補完推奨)背景
私はROSもUnityも大好きなので、両方組み合わせると楽しいということをお伝えしたくて、光り物(VJツール)を作ってみることにしました。
これをやることになった一番のきっかけは、ギャル電さんの名言「とりまつないで光ればいいじゃん?」([出典]ギャル電とつくる! バイブステンアゲサイバーパンク光り物電子工作) であることは言うまでもありません。
つまり ROS + Unity → 光る → 楽しい! ということです!
対象読者
この記事はROSとUnityそれぞれ使った経験のある方を対象としています。
初めての方は「UnityとROSで学ぶ移動ロボット入門 UI作成編」や「Unity Robotics Hub」で使い方を覚えてみてください。
今回作るもの
LiDARから得られた3次元点群を入力とし、その点群にUnity上で様々なエフェクトを掛けて楽しむVJツールです。
なぜROSとUnityを組み合わせるのか
ROSとUnityを組み合わせると良い事だらけです。例えば、
- ROS対応している豊富なセンサーやアクチュエータが使える
- 入力を拡張しやすい
- カメラ、LiDAR、ボタン、ロータリーエンコーダ、力触覚デバイス、IMUなどありとあらゆるデバイスが容易に繋がる
- 出力も拡張しやすい
- 映像に合わせてサーボモーターを動かしたり、ロボットにパフォーマンスさせたり、遠隔地の機器を動かすことも出来る
つまりROSのエコシステムとUnityを組み合わせによって、機材や時空間の制約も超えたあらゆる表現が可能となるのです。そんなヤバいやつが手軽に作れるので超ヤバいです!
さてさて、期待も高まったところで早速作っていきましょう!
用意するもの
名称 | URLなど | 備考 |
---|---|---|
Ubuntuの入ったPC | 出来れば18.04だと簡単ですが、今回は20.04を使います | |
Docker | https://www.docker.com/ | Ubuntu 18.04を使うのであれば不要です |
ROS | https://ros.org/ | LiDARのドライバの都合でMelodicを使います |
Unity | https://unity.com/ | UbuntuのPCにインストールしておきます。GraphicsBufferを使いたいのでバージョンは2021.2以降で。 |
ROS TCP Endpoint | https://github.com/Unity-Technologies/ROS-TCP-Endpoint | ROSとUnityの接続用(ROS側) |
ROS TCP Connector | https://github.com/Unity-Technologies/ROS-TCP-Connector | ROSとUnityの接続用(Unity側) |
Cygbot CygLiDAR D1 | https://www.switch-science.com/catalog/7460/ | ROSドライバがあるLiDAR。ちょうど手元にあったのでこれを使いますが、V社とかH社とかのでも良いと思います。 |
MIDIコントローラー | 様々なものがあるのでお好みのものを使って下さい |
システム構成
CygLiDAR D1の動作確認(この作業は必須ではありません)
一旦CygLiDAR D1をWindows 10か11に接続して、CygLiDAR Viewerを使って動作確認してみます。
このダウンロードページにある英語版のマニュアルを読みながらセットアップしていきます。ただしドライバは手動でインストールする必要がありました。
マニュアルにある通り、ダウンロード先のWebサイトからZIP形式で配布されているドライバのセットアッププログラムをダウンロードして展開します。
するとZIPの中に PL2303G
用と PL2303D
用の2つのファイルが存在しています。
今回どちらが正解か良くわからなかったので、当てずっぽうで PL2303D
で始まる方の SER2PL_1.inf
を選択してインストールしてみたら動いたので、多分これで大丈夫です。
CygLiDAR D1はUSBで接続するとシリアルデバイスに見えます。
その後CygLiDAR Viewerを起動してみるとこのように見えます。この画面だけでもかなりいい感じですね。
これでひとまず動作確認はOK。
さて、ここからが本題。
CygLiDAR D1のUSBドライバをホスト側にインストールする
CygLiDAR D1はデフォルトではシリアルデバイス(/dev/ttyUSB?
)に見えますが、接続時にこのudevルールを適用することで誰でも読み書き可能な/dev/cyglidar
というデバイスファイルへのシンボリックリンクを張ってくれるようになり、アプリケーションはこのデバイスファイルにアクセスすることで、点群を取得出来るようになります。
このudevルールファイルのインストール処理はcreate_udev_rules.shというスクリプトでやることになっているのですが、catkin_make
とdev/setup.bash
が成功した後で無いとこのスクリプトは実行できませんので、ちょっとハックします。(中でrospack
を実行してるから)
create_udev_rules.sh
の中を見てみると必要なのは以下の3行だけでした。
sudo cp `rospack find cyglidar_d1`/scripts/cyglidar.rules /etc/udev/rules.d
sudo service udev reload
sudo service udev restart
問題があるのは1行目なので、これを以下のように書き換えて実行すれば大丈夫です。
sudo cp [cyglidar.rulesのあるディレクトリ]/cyglidar.rules /etc/udev/rules.d
sudo service udev reload
sudo service udev restart
うまく行けば以下のように表示されます。
sudo ./create_udev_rules.sh
Remap the device serial port(ttyUSBX) to cyglidar
Check if USB is identified as /dev/cyglidar using the command: ls -l /dev|grep ttyUSB
Start copying cyglidar.rules to /etc/udev/rules.d/
./create_udev_rules.sh: line 7: rospack: command not found
/scripts/cyglidar.rules
Restart udev
Created
ROS側の準備
概要
ホストのUbuntu PCにDockerを入れてROSをセットアップしていきます。
今回使用するCygLiDAR D1用のROSパッケージと、このパッケージ内から使用されるドライバはLinux用ですので、Linux PCが必要です。本記事ではホストにUbuntu 20.04を使用しています。
CygLiDAR D1用のROSパッケージはROS Melodicではcatkin_make
が成功するものの、Noeticではcatkin_make
は失敗してしまいます。
Ubuntu 20.04上でもMelodicを利用したいので、Dockerをインストールしてその上でMelodicを実行し、さらにその上でCygLiDAR D1用のROSパッケージを使うことにします。
Dockerコンテナを実行する
CygLiDAR D1をホスト PCにUSBで接続し/dev/cyglidar
が生成されていることを確認してから、以下のコマンドでDockerイメージを実行します。
docker run -it --rm -p 6080:80 -p 10000:10000 -p 5005:5005 --shm-size=512m --device /dev/cyglidar:/dev/cyglidar ros-desktop-vnc-melodic
ここでのDockerイメージは@Tiryoh さんのの作られたMelodicのイメージros-desktop-vnc-melodic
を使わせていただきました。(@Tiryoh さん、いつもお世話になっています!)
CygLiDAR D1のトピックをUnity側からサブスクライブ出来るようにする
Webブラウザを起動して、127.0.0.1:6080
にアクセスします。
LXTerminalを起動して、以下のコマンドを実行して、CygLiDAR D1のROSパッケージとROS TCP Endpointを使えるようにします。
cd ~/catkin_ws/src
git clone https://github.com/CygLiDAR-ROS/cyglidar_d1.git
git clone https://github.com/Unity-Technologies/ROS-TCP-Endpoint.git
pushd ROS-TCP-Endpoint && git checkout v0.6.0 && popd
cd ..
catkin_make
source devel/setup.bash
次に、ROS_IP等を設定します。ここで使うスクリプトは「UnityとROSで学ぶ移動ロボット入門 UI作成編」から以下のようにしてダウンロードして利用します。
cd ~
curl -O https://raw.githubusercontent.com/unity3d-jp/Unity-ROS-MobileRobot-UI-Tutorial/062ba39ee6b4ca1ee05d94e20638278e8ef88dcb/ROS/configure.sh
chmod +x configure.sh
./configure.sh
これで、ROS TCP Connectorのconfig.yamlに正しいROS_IPが設定され、ホスト側のUnityのROS TCP Connectorと接続できるようになりました。
CygLiDAR D1から点群データを取得する
既に開いている方のターミナルで以下のコマンドを実行します。
roslaunch cyglidar_d1 cyglidar.launch
RVizが表示され、CygLiDAR D1から取得された点群が表示されるかと思います。
ROS TCP Endpointを起動する
続いて、もう一つのターミナルを開いて以下のコマンドを実行し、ROS TCP Endpointを起動します。
cd ~/catkin_ws
source devel/setup.bash
roslaunch ros_tcp_endpoint endpoint.launch
以上でUnityのROS TCP Connectorを使ってサブスクライブされたROSトピックがパブリッシュされるようになりました。
最終的にROS側はこのスクリーンショットのような表示になります。
Unity側の準備
Unity HubやUnityエディタのインストールが済んでいる状態から解説していきます。
今回の見せ場である点群の可視化方法はいろいろあって、効率や拡張のしやすさの面からいえばVisual Effect Graph(VFX Graph)などを利用したGPUパーティクルが良いのですが、最初は基礎的な知識だけで利用可能で実装も簡単なプレハブ化されたメッシュを使った方法を採用します。VFX Graphを使う方法は拡張編でご紹介します。
新規HDRPプロジェクトの作成
手間を掛けずに派手な絵を出したいのでHDRPの力を借ります。
まずUnity Hubから 3D Sample Scene (HDRP)
を選び、新規プロジェクトを作成します。(Unity Hubのバージョンによっては、テンプレート名が High Definition RP
の場合もあります)
ROS TCP Connectorをインストールする
パッケージマネージャからROS TCP Connectorをインストールをインストールします。
方法はROS TCP Connectorの Installation を参照して下さい。
新規シーンを作成する
新規シーンを作成し、Main Camera
、Directional Light
、点群の発生の起点にするPointCloudRoot
そして様々なエフェクトをかけるためのGlobal Volume
を追加します。
新規マテリアルを作成する
新しいマテリアルを作成しHDRP/Lit
シェーダーを設定し、Surface Type
をTransparent
にします。
このマテリアルが、各点の位置に表示するオブジェクトのためのマテリアルとなります。
マテリアル名はLitTransparent
にしておきます。
プレハブを作成しマテリアルを設定する
各点の位置に描画するメッシュオブジェクトのプレハブを作成します。
例えばPlane、Cube、Sphereなどが手軽です。
あまり頂点数が多いと、描画負荷が上がりすぎることもありますので、処理負荷を考慮しつつ、適切なメッシュを選択して下さい。
マテリアルには先程作成したLitTransparent
を設定しておきます。
scan_3Dトピックをサブスクライブしプレハブのインスタンスを配置して描画する
CygLiDAR D1のROSノードは、scan_2D
、scan_3D
そしてscan_laser
の3つのトピックをパブリッシュしますが、今回はscan_3D
トピックでパブリッシュされているPointCloud2メッセージをサブスクライブして、各点の位置にプレハブのインスタンスを描画してみることにします。
この機能を実現するためのスクリプトは次のように書けて、これをPointCloudRoot
にアタッチしておきます。
using RosMessageTypes.Sensor;
using System;
using UnityEngine;
using Unity.Robotics.ROSTCPConnector;
using Unity.Robotics.ROSTCPConnector.ROSGeometry;
// ROSのscan_3Dトピックをサブスクライブし、各点の位置にプレハブで指定されたGameObjectのインスタンスを配置して描画するクラス
public class Scan3DSubscriber : MonoBehaviour
{
[SerializeField] string rosTopicName = "scan_3D";
[SerializeField] GameObject pointPrefab;
private GameObject[] pointObjs;
void Start()
{
// scan_3Dトピックをサブスクライブする
ROSConnection.GetOrCreateInstance().Subscribe<PointCloud2Msg>(rosTopicName, Callback);
}
// scan_3DトピックのPointCloud2Msgを受信したときに呼ばれるコールバック
void Callback(PointCloud2Msg message)
{
if (message.data == null || message.data.Length == 0)
return;
if (message.fields.Length != 4 || message.fields[0].datatype != 7 || message.is_bigendian)
return; // 簡単のため、各点の座標の各要素の型がfloat32かつリトルエンディアンのときだけ処理することにする
int width = (int)message.width; // 水平方向の点の個数
int height = (int)message.height; // 垂直方向の点の個数
// int row_step = (int)message.row_step;
int point_step = (int)message.point_step; // 次の点までのオフセット
int offset_x = (int)message.fields[0].offset; // X座標のオフセット
int offset_y = (int)message.fields[1].offset; // Y座標のオフセット
int offset_z = (int)message.fields[2].offset; // Z座標のオフセット
int offset_rgba = (int)message.fields[3].offset; // 色のオフセット
int count = message.data.Length / point_step;
// 各点の位置に描画するGameObjectを初期化する
if (pointObjs == null)
{
pointObjs = new GameObject[count];
for (int n = 0; n < pointObjs.Length; n++)
{
pointObjs[n] = Instantiate(pointPrefab, transform);
}
}
else if (pointObjs.Length != count)
{
for (int n = 0; n < pointObjs.Length; n++)
{
Destroy(pointObjs[n]);
}
pointObjs = new GameObject[count];
for (int n = 0; n < pointObjs.Length; n++)
{
pointObjs[n] = Instantiate(pointPrefab, transform);
}
}
// 取得された点の個数分だけ繰り返し
for (int n = 0; n < count; n++)
{
int step = n * point_step;
int ix = step + offset_x;
int iy = step + offset_y;
int iz = step + offset_z;
int irgba = step + offset_rgba;
float x = BitConverter.ToSingle(message.data, ix);
float y = BitConverter.ToSingle(message.data, iy);
float z = BitConverter.ToSingle(message.data, iz);
uint rgba = BitConverter.ToUInt32(message.data, irgba);
// ROSの座標系からUnityの座標系に変換する
Vector3 p = (new Vector3<FLU>(x, y, z)).toUnity;
// 各GameObjectの位置を各点の位置に合わせる
pointObjs[n].transform.localPosition = p;
// 各GameObjectのメッシュの色をROS側から送られてきた色にする
Material mat = pointObjs[n].GetComponent<MeshRenderer>().material;
float r = ((rgba & 0xff000000) >> 24) / 255f;
float g = ((rgba & 0xff0000) >> 16) / 255f;
float b = ((rgba & 0xff00) >> 8) / 255f;
float a = (rgba & 0xff) / 255f;
Color c = new Color(r, g, b, a);
mat.SetColor("_BaseColor", c);
}
}
}
Playして調整する
ROS側は既に各launchファイルが起動しているものとして、この段階でPlayしてみるとこのような表示になるかと思います。(見え方はCygLiDAR D1が捉えたデプス値によって変わります)
もうちょっと輪郭がはっきり見えるように、メッシュオブジェクトのスケールや、Global VolumeのVolume
コンポーネントのPost Effect
で、Exposure
をオーバーライドしてIntensity
を調整してみましょう。
Post Effect
でいろいろな属性をオーバーライドしていじってみると、簡単に見た目を変えることが出来て楽しいです。
今回のプロジェクトではHDRPを使っていますが、HDRPの良いところはこのような調整の幅がとても広く、しかも少しぐらい無茶な設定をしても絵が破綻しないところです。実行環境のスペックさえ許せば、HDRPはとても便利です。
さて、いかがでしょうか? ROSとUnityでVJツールを作る事の魅力を少しでも感じていただけたら嬉しいです。
拡張編 MIDIコントローラーを使う
ROS経由でMIDIコントローラー使えるようにして、インタラクティブ性を高める方法についてご紹介したいと思います。
Unityから直接MIDI扱う方法は高橋啓治郎さんが紹介しているこちらやこちらなどがありますが、今回はROS側からMIDIコントローラーのメッセージをパブリッシュする方法をご紹介します。
ここでご紹介するやり方は、ロボットの調整用のUIを構築する際にも役に立つと思いますよ。
ホスト側の準備
MIDIコントローラーを接続しデバイスファイルを確認します。
ls /dev/midi*
/dev/midi3
などと表示されればOKです。
次にaconnect
コマンドを使って、MIDIデバイス名を確認します。
$ aconnect -l
私は今回 Launch Key Mini MK3 というMIDIキーボードを接続しました。その時の aconnect -l
の結果は以下のようになりました。
$ aconnect -l
client 0: 'System' [type=kernel]
0 'Timer '
1 'Announce '
client 14: 'Midi Through' [type=kernel]
0 'Midi Through Port-0'
client 28: 'Launchkey Mini MK3' [type=kernel,card=3]
0 'Launchkey Mini MK3 MIDI 1'
1 'Launchkey Mini MK3 MIDI 2'
これらのMIDIデバイスをDocker側でも使えるようにするために、一度これまでの作業が済んだdockerコンテナをcommitして終了し、デバイスオプションを付け直して起動します。
まずは動いているコンテナをコミットします。
$ docker ps
[コンテナID] ros-desktop-vnc-melodic (以下略)
$ docker commit [コンテナID] desktop-vnc-melodic-version2
--device /dev/midi3:/dev/midi3 --device /dev/snd/seq:/dev/snd/seq
を足して、先程コミットしたイメージを起動します。
docker run -it --rm -p 6080:80 -p 10000:10000 -p 5005:5005 --shm-size=512m --device /dev/cyglidar:/dev/cyglidar --device /dev/midi3:/dev/midi3 --device /dev/snd/seq:/dev/snd/seq ros-desktop-vnc-melodic-version2
Docker側の準備
プログラムからMIDIを扱うにはいろいろなやり方がありますが、今回は実装が簡単な mido というライブラリを使って、PythonスクリプトからMIDIコントローラーからの入力イベントを取得します。
mido
を使うためには、以下のインストールが作業が必要です。
sudo apt install libasound2-dev
sudo apt install libjack-dev
sudo apt install python-pip
pip install -U mido
pip install -U python-rtmidi
MIDIコントローラーからの入力イベントを拾ってみる
import mido
# 確認のため入力ポート名を列挙する
device_names = mido.get_input_names()
for device_name in device_names:
print(device_name)
input_name = 'Launchkey Mini MK3:Launchkey Mini MK3 MIDI 1 28:0' # ここはお使いのコントローラーによって変えて下さい
with mido.open_input(input_name) as inport:
for message in inport:
if message.type == 'note_on':
print(message)
elif message.type == 'note_off':
print(message)
elif message.type == 'control_change':
print(message)
elif message.type == 'pitchwheel':
print(message)
このスクリプト実行して試しに鍵盤とツマミを操作してみると、以下のような結果が得られます。
$ python mido_input_test.py
Midi Through:Midi Through Port-0 14:0
Launchkey Mini MK3:Launchkey Mini MK3 MIDI 1 28:0
Launchkey Mini MK3:Launchkey Mini MK3 MIDI 2 28:1
Midi Through:Midi Through Port-0 14:0
Launchkey Mini MK3:Launchkey Mini MK3 MIDI 1 28:0
Launchkey Mini MK3:Launchkey Mini MK3 MIDI 2 28:1
note_on channel=0 note=48 velocity=75 time=0
note_off channel=0 note=48 velocity=0 time=0
note_on channel=0 note=48 velocity=80 time=0
note_off channel=0 note=48 velocity=0 time=0
control_change channel=0 control=21 value=0 time=0
control_change channel=0 control=21 value=1 time=0
control_change channel=0 control=21 value=2 time=0
ROS側でMIDIイベントをROSのStringメッセージとしてパブリッシュする
上記の通り、MIDIイベントは note_on
や control_change
など、タイプによって内容が異なります。
カスタムメッセージを定義しても良いのですが、今回は std_msgs/String
としてパブリッシュして、Unity側でパースすることにします。
まず mido_input
というパッケージを作ります。
cd ~/catkin_ws/src
catkin_create_pkg mido_input rospy std_msgs
次に先程の mido_input_test.py
を以下のように書き換え、~/catkin_ws/src/mido_input/scripts/
に mido_input_publisher.py
という名前で保存します。
#!/usr/bin/env python
import rospy
from std_msgs.msg import String
import mido
input_name = 'Launchkey Mini MK3:Launchkey Mini MK3 MIDI 1 28:0'
def main():
rospy.init_node("publisher")
pub = rospy.Publisher("mido_input", String, queue_size=10) #トピック名は mido_input にする
rate = rospy.Rate(10)
inport = mido.open_input(input_name)
while not rospy.is_shutdown():
for message in inport.iter_pending():
if message.type == 'note_on':
msg = str(message)
pub.publish(msg)
rospy.loginfo("Message '{}' published".format(msg))
elif message.type == 'note_off':
msg = str(message)
pub.publish(msg)
rospy.loginfo("Message '{}' published".format(msg))
elif message.type == 'control_change':
msg = str(message)
pub.publish(msg)
rospy.loginfo("Message '{}' published".format(msg))
elif message.type == 'pitchwheel':
msg = str(message)
pub.publish(msg)
rospy.loginfo("Message '{}' published".format(msg))
rate.sleep()
if __name__ == "__main__":
main()
mido_input_publisher.py
に実行権限を付けておきます。
chmod +x ~/catkin_ws/src/mido_input/scripts/mido_input_publisher.py
~/catkin_ws/src/mido_input/launch
に mido_input.launch
という名前でlaunchファイルを作ります。
<launch>
<node pkg="mido_input" name="mido_input_publisher" type="mido_input_publisher.py" output="screen" />
</launch>
launchファイルを実行して、MIDI入力をmido_input
トピックとしてパブリッシュします。
cd ~/catkin_ws
catkin_make
source devel/setup.bash
roslaunch mido_input mido_input.launch
以上でUnity側で mido_input
トピックをサブスクライブする準備が整いました。
Unity側でmodo_inputトピックをサブスクライブしてPost Processingの属性を制御する
ノート番号60(C4)ONでモノクロに、コントロールチェンジ21番を操作すると露出が変わるようにしてみます。
下記のスクリプトを書いて、適当なGameObjectにアタッチし、VolumeにGlobal Volumeを設定します。
using RosMessageTypes.Std;
using UnityEngine;
using UnityEngine.Rendering;
using UnityEngine.Rendering.HighDefinition;
using Unity.Robotics.ROSTCPConnector;
public class StringSubscriber : MonoBehaviour
{
[SerializeField] string rosTopicName = "mido_input";
[SerializeField] Volume volume;
private Exposure exposure;
private ColorAdjustments colorAdjustments;
// Start is called before the first frame update
void Start()
{
// ROSトピックをサブスクライブ
ROSConnection.GetOrCreateInstance().Subscribe<StringMsg>(rosTopicName, Callback);
// Post Processingの属性を変更できるようにする
Exposure tmpExposure;
if (volume.profile.TryGet<Exposure>(out tmpExposure))
{
exposure = tmpExposure;
}
ColorAdjustments tmpColorAdjustments;
if (volume.profile.TryGet<ColorAdjustments>(out tmpColorAdjustments))
{
colorAdjustments = tmpColorAdjustments;
}
}
void Callback(StringMsg message)
{
Debug.Log(message.data);
string[] data = message.data.Split(' ');
if (data.Length < 5)
return;
if (data[0] == "note_on") // ノートON
{
// e.g.: note_on channel=0 note=60 velocity=79 time=0
string[] note = data[2].Split('=');
int num = int.Parse(note[1]);
if (num == 60)
{
colorAdjustments.saturation.value = -100f;
}
}
else if (data[0] == "note_off") // ノートOFF
{
string[] note = data[2].Split('=');
int num = int.Parse(note[1]);
if (num == 60)
{
colorAdjustments.saturation.value = 0f;
}
}
else if (data[0] == "control_change") // コントロールチェンジ
{
// e.g.: control_change channel=0 control=21 value=0 time=0
string[] control = data[2].Split('=');
string[] value = data[3].Split('=');
int num = int.Parse(control[1]);
int val = int.Parse(value[1]);
if (num == 21)
{
float f = Remap(val, 0, 127, -5, 15);
if (exposure)
exposure.fixedExposure.value = f;
}
}
else if (data[0] == "pitchwheel") // ピッチベンド
{
}
}
float Remap(float value, float a, float b, float newA, float newB)
{
return (value - a) / (b - a) * (newB - newA) + newA;
}
}
拡張編 VFX Graphを使って描画を高速化する
いよいよこの記事の最後のネタ、点群の座標と色をGraphicsBufferを経由してVFX Graphに渡しGPUパーティクルとして描画してみます。
こうすることで、上記で説明したプレハブのインスタンスを使う場合に比べて大幅な高速化が実現できます。
こちらがVFX Graphで点群の位置にキューブを描画したときの様子です。
画面下部のProfilerの表示を見てみると 120fps以上出せる能力(GeForce RTX 3070使用時)があることがわかります。
実装
実装方法はこちらの記事「VFX GraphにGraphicsBufferを渡す」を参考にさせてもらいました。
まず、点群をGraphicsBufferに詰めて、VFX Graphに渡すスクリプトです。こちらを応用しています。
using RosMessageTypes.Sensor;
using System;
using System.Runtime.InteropServices;
using UnityEngine;
using UnityEngine.VFX;
using Unity.Robotics.ROSTCPConnector;
using Unity.Robotics.ROSTCPConnector.ROSGeometry;
public class PointCloud2SubscriberVfx : MonoBehaviour
{
[SerializeField] string rosTopicName = "scan_3D";
private GraphicsBuffer colorBuffer = null;
private GraphicsBuffer positionBuffer = null;
private Color[] colorArray = null;
private Vector3[] positionArray = null;
private readonly int _propertyColorBuffer = Shader.PropertyToID("colorBuffer");
private readonly int _propertyPositionBuffer = Shader.PropertyToID("positionBuffer");
[SerializeField] private VisualEffect _effect;
void Start()
{
ROSConnection.GetOrCreateInstance().Subscribe<PointCloud2Msg>(rosTopicName, Callback);
}
void Callback(PointCloud2Msg message)
{
if (message.data == null || message.data.Length == 0)
return;
if (message.fields.Length != 4 || message.fields[0].datatype != 7 || message.is_bigendian)
return; // for now, only 7 (= float32) and Little Endian is supported
int width = (int)message.width;
int height = (int)message.height;
int row_step = (int)message.row_step;
int point_step = (int)message.point_step;
int offset_x = (int)message.fields[0].offset;
int offset_y = (int)message.fields[1].offset;
int offset_z = (int)message.fields[2].offset;
int offset_rgba = (int)message.fields[3].offset;
int count = message.data.Length / point_step;
if (colorBuffer == null || colorBuffer.count != count)
{
if (colorBuffer != null)
{
colorBuffer.Dispose();
}
colorBuffer = new GraphicsBuffer(
GraphicsBuffer.Target.Structured,
count,
Marshal.SizeOf(new Color())
);
colorArray = new Color[count];
_effect.SetGraphicsBuffer(_propertyColorBuffer, colorBuffer);
}
if (positionBuffer == null || positionBuffer.count != count)
{
if (positionBuffer != null)
{
positionBuffer.Dispose();
}
positionBuffer = new GraphicsBuffer(
GraphicsBuffer.Target.Structured,
count,
Marshal.SizeOf(new Vector3()));
positionArray = new Vector3[count];
_effect.SetGraphicsBuffer(_propertyPositionBuffer, positionBuffer);
}
for (int n = 0; n < count; n++)
{
int step = n * point_step;
int ix = step + offset_x;
int iy = step + offset_y;
int iz = step + offset_z;
int irgba = step + offset_rgba;
float x = BitConverter.ToSingle(message.data, ix);
float y = BitConverter.ToSingle(message.data, iy);
float z = BitConverter.ToSingle(message.data, iz);
uint rgba = BitConverter.ToUInt32(message.data, irgba);
positionArray[n] =(new Vector3<FLU>(x, y, z)).toUnity;
float r = ((rgba & 0xff000000) >> 24) / 255f;
float g = ((rgba & 0xff0000) >> 16) / 255f;
float b = ((rgba & 0xff00) >> 8) / 255f;
float a = (rgba & 0xff) / 255f;
colorArray[n] = new Color(r, g, b, a);
}
colorBuffer.SetData(colorArray);
positionBuffer.SetData(positionArray);
}
void OnApplicationQuit()
{
if (colorBuffer != null)
{
colorBuffer.Dispose();
colorBuffer = null;
}
if (positionBuffer != null)
{
positionBuffer.Dispose();
positionBuffer = null;
}
}
}
VFX Graphは以下のような構成です。こちらの AKDK-PointCloud.vfx
を応用しています。
以上をPointCloud2Subscriberの代わりに用いることで、VFX Graphを用いた高速描画や様々なエフェクトが実現出来るようになり、表現の幅が広がりまくります。
参考文献
以下は上記で書ききれなかった参考情報です。作者の方に感謝いたします!!
- ROS/ROS2のGUIをWebブラウザ経由でお手軽に試せるDockerfileを公開しました
- Docker上でGUIのROS1/ROS2を一瞬でセットアップする方法
- dockerでウェブカメラの映像を表示する
- ROS#でのPCL2(PointCloud2)の扱い方
- Unity Robotics Hub 入門
- Mido Documentation
- Rsvfx
おわりに
LiDARの点群を素材したVJツールを開発しました。
実際にやってみて、ROSのエコシステムが持つ極めて高いポテンシャルはロボットだけには留まらないことを肌身で感じることが出来ました。
今後はまとまった成果をオープンソースとして公開することで、ROSおよびUnity開発者コミュニティの発展に貢献していきたいと考えています!