このブログは、株式会社フィックスターズのエンジニアが、あらゆるテーマについて自由に書いているブログです。
こんにちは。アルバイトの木村です。
この記事では、インターンシップで開発した、3D Gaussian Splatting向けのデータセット作成システムについて紹介します。
このシステムの最大の特徴は、一般的なカメラ画像に加えて、LiDARから得られる正確な点群も活用する点です。開発にはROS2やSLAMといった技術を活用しました。
本記事では、このシステムがどういった実装になったのかや、実際に会議室を測定した結果、どのようなデータが取得でき、どのような課題が見えたのかを詳しく解説します。
3D Gaussian Splatting for Real-Time Radiance Field Renderingは、複数の画像から、高品質な3Dシーンを生成し、それを高速にレンダリングする2023年に発表された新しい技術です。別記事3D Gaussian Splatting の紹介と高速化にも解説がありますので、そちらもあわせてご覧ください。
3D Gaussian Splatting(3DGS)は、異なる画角から撮影された複数の画像から物体の3次元形状を推定します。従来の手法と比べて綺麗にかつ高速に3Dモデルを表示できることが大きな特徴です。
3DGSを行う際には、静的なシーンを撮影した複数の画像に加えて、画像ごとに「撮影したカメラの位置や向きの情報」が必要になります。画像だけではどこから撮影したのかがわからないためです。
これらのカメラの情報は、Structure from Motion(SfM)と呼ばれる手法によって推測されたものを用いることが一般的です。SfMでは、写真の中の共通の目印(特徴点)を複数枚の写真で照らし合わせることで、カメラの姿勢を割り出し、同時に3Dモデルの元となる疎な点群を作成します。
画像からカメラの姿勢を推測するSfMという技術は、撮影する場所や物によっては正しく機能しないことがあります。例えば、単色の壁のようにのっぺりとした特徴のない場所では、目印をみつけることができず、うまく計算できないことがあります。また、レンガの壁や規則的なパターンの床といった同じ模様が繰り返し続く環境では、特徴点のマッチングで失敗しやすいといった課題があります。
そこで、3D LiDARが活用できないか検討しました。3D LiDARは、レーザー光を用いて対象物の距離を測定し点群を取得する技術で、自動運転や移動ロボットなどで利用されています。取得した点群のマッチングを行うことで、リアルタイムで自己位置推定やマップ生成を行うことができます。点群を得る原理が異なるので、先ほど示したカメラが苦手とするシーンにおいても3D LiDARと組み合わせることで3DGSを行うことが可能になると考えています。下の画像は、会議室で取得した点群の様子です。
これに加えて、密な点群を収集できることも3D
LiDARを用いる利点であると考えています。
3DGSでは、はじめに初期点群を入力することも可能であり、ランダムな点群からよりもSfMによって出力された疎な点群から初期化を行うほうが生成される3Dガウシアンの品質が高いことが論文中で示されています。また、疎な点群から段階的に高密度化を行うのではなく、画像間から三角測量によって得られる密な点群を用いることで処理を高速化するEDGS: Eliminating Densification
for Efficient Convergence of
3DGSという手法も今年発表されています。3D
LiDARを用いて高密度で正確な点群を取得できれば、これらに似た効果を得られるのではないかと考えました。
LiDARを用いてデータセットを製作し、3DGSを行う先行研究としてはLetsGo: Large-Scale Garage Modeling and Rendering via LiDAR-Assisted Gaussian Primitivesが挙げられます。この研究では魚眼カメラと3D LiDARをセットにしたハンドスキャナを用いていることについて記載がありますが、データセットを作る際にどういった点が重要なのかについてはわからないことも多いです。
そこで、実際に3D LiDARとカメラを組み合わせて、どのようなデータが得られるか検証しました。
下記に示すようなシステム(通称: カメライダーKIMURAシステム)を作成しました。
カメライダーKIMURAシステムでは、LiDARとカメラから得られるデータを統合し、色情報を持つ3次元点群データを生成します。
まず、LiDARからはSLAM技術の一種であるFAST-LIOを用いて、「3次元点群セット」と「自己位置情報(オドメトリ)」を取得します。並行して、カメラからは「画像データ」を撮影します。
次に、LiDARのオドメトリとカメラの画像を、それぞれのタイムスタンプを基準に時刻同期させます。
最後に、この時刻同期したデータと、事前にキャリブレーションで計測しておいたカメラの内部パラメータを活用します。LiDARのオドメトリとの位置関係からカメラの姿勢を算出し、その情報を使って3次元点群の各点に画像の色情報を付与(カラーマッピング)します。
※カメラはUSBカメラのPlayStation Eyeを、LiDARはOuster
OS0-32を使用しています。
カメラは解像度640×480、60fpsの設定で画像を取得します。LiDARの測定距離は最小0.3mから、反射率80%の対象物で最大45m(反射率10%時は15m)まで検出可能です。垂直解像度は32ライン、水平解像度と回転レートについてはデフォルト設定である1024×10Hzを使用しています。
次節にて、個々の詳細について解説していきます。
Ousterは公式のROSパッケージが出ているのでそれに沿ってROSの環境構築とドライバのインストールを行います。今回のインターンでは用いたPCの環境がubuntu20.04だったのでディストリビューションはROS2 foxyで環境構築しました。
READMEにも書いてありますが、ROSの環境設定を行った後、クローンする際に
--recurse-submodulesをつけておかないと、SDKが正しく落とせないので注意が必要です。
PCとつなぐ際のネットワーク設定はこちらを参考に設定します。正しくネットワーク接続ができると、os-[serial-number].localからLiDARについての情報を表示できるようになります。ここのserial-numberはLiDAR上に記されている12桁の番号です。
ここで、ファームウェアのバージョンが古いとうまく動かないことがあります。そういった際は公式のリポジトリからダウンロードしてきてファームウェアをアップデートします。この際、Hardware
versionはLiDAR本体に記されているので、それに合わせて最新のものを選択します。今回用いたものだと、840-10****-06に当てはまるのでハードウェアのバージョンはRev.06であるという具合に判断できます。
LiDARからデータをとれるようになったら、次はSLAMを使用してオドメトリや点群情報をとれるようにします。
使用するSLAMですが、今回はFAST-LIOを使用しました。今回用いているOusterのLiDARが使用可能かつ、ROS2に対応しているものを選択しました。
使用する際ですが、まず、手元のOusterに対応させるためにyamlファイルを作成します。configディレクトリにyamlファイルを追加し、手元の仕様を記入します。今回の場合、commonにOusterの公式パッケージで出されるトピック名を記入し、preprocessに垂直方向の解像度である32を記入します。ouster64.yamlを参考に作成しました。
一部抜粋(ouster32.yaml)
common:
lid_topic: "/ouster/points"
imu_topic: "/ouster/imu"
preprocess:
lidar_type: 3 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
scan_line: 32
timestamp_unit: 3 # 0-second, 1-millisecond, 2-microsecond, 3-nanosecond.
これでOusterをROS2上で起動してからFAST-LIOを起動するとLiDARの自己位置や点群情報がとれるようになります。オドメトリは/Odometry、点群は/point_cloudトピックとしてデータ取得できます。
また、点群の情報については、測定中の情報から1つの点群マップをFAST-LIO終了時に保存する機能があります。この機能を使うためには、src/laser_mapping.cpp中の513行目付近からのコメントアウトを外す必要があります。yamlファイルのpcb_save_en:trueだけでは使用できないので、注意が必要です。
/**************** save map ****************/
/* 1. make sure you have enough memories
/* 2. noted that pcd save will influence the real-time performences **/
if (pcd_save_en)
{
int size = feats_undistort->points.size();
PointCloudXYZI::Ptr laserCloudWorld( \
new PointCloudXYZI(size, 1));
for (int i = 0; i < size; i++)
{
RGBpointBodyToWorld(&feats_undistort->points[i], \
&laserCloudWorld->points[i]);
}
*pcl_wait_save += *laserCloudWorld;
static int scan_wait_num = 0;
scan_wait_num ++;
if (pcl_wait_save->size() > 0 && pcd_save_interval > 0 && scan_wait_num >= pcd_save_interval)
{
pcd_index ++;
string all_points_dir(string(string(ROOT_DIR) + "PCD/scans_") + to_string(pcd_index) + string(".pcd"));
pcl::PCDWriter pcd_writer;
cout << "current scan saved to /PCD/" << all_points_dir << endl;
pcd_writer.writeBinary(all_points_dir, *pcl_wait_save);
pcl_wait_save->clear();
scan_wait_num = 0;
}
}
今回のデータ測定では、点群情報についてはこの出力結果を使用しています。
カメラのデータ取得についても、LiDARと同様にROS2上で行います。v4l2(Video for Linux 2)を使用します。ROS2のパッケージがaptシステムで入手できるので、環境構築が容易に行えます。使用する際は、使用するデバイスを確認したうえで
ros2 run v4l2_camera v4l2_camera_node --ros-args -p video_device:=/<device_location>
でROSノードとして使用できるようになります。ここから出力されているraw_imageを取得します。
また、カメラの内部パラメータを得るためにカメラのキャリブレーションを行います。ROSの公式で提供されているcamera_calibrationを使用します。チェッカーボードを公式が提供しているものなどを用いて表示、あるいは印刷して、camera_calibrationを起動し、複数のデータが集まるように撮影することでデータ取得ができます。ここで、複数項目すべてをクリアするだけの枚数を撮らないと正しくキャリブレーションができないので注意が必要です。以下コマンドで起動します。--sizeで何マス×何マスのチェッカーボードなのかと、--squareで正方形の一片の長さを指定します。
ros2 run camera_calibration cameracalibrator --size <*x*> --square <squre_length> --ros-args -r image:=/image_raw
カメラで得た画像データとLiDARから得たデータはそれぞれ違うデバイスからデータを取得しているので、時刻同期を行う必要があります。
今回はROS2を使っているので、それぞれのトピックのタイムスタンプを比較して実装しました。タイムスタンプから一定時間以内のROSトピック同士を同じ時刻のデータとしてrosbagに保存する形でノードを自作しました。
この際、LiDARから得たデータはReliabilityがBest effortである点に注意が必要です。デフォルトはReliableなので、LiDARからのトピックを得るSubscriberのQoSはSensorDataQoSと明確に指定しないとデータが取れません。
lidar_sub_ = create_subscription<sensor_msgs::msg::PointCloud2>(
"/ouster/points", rclcpp::SensorDataQoS(), std::bind(&ManualSync::lidar_callback, this, _1));
また、Ousterが出すタイムスタンプもデフォルトでROS_TIMEになっていないので、Ousterのlaunchファイルを編集して設定する必要があります。変数のところのtimestamp_nodeが該当箇所なのでそこのdefault値を変えることでタイムスタンプを揃えることができます。
<arg name="timestamp_mode" default="TIME_FROM_ROS_TIME"
description="method used to timestamp measurements; possible values: {
TIME_FROM_INTERNAL_OSC,
TIME_FROM_SYNC_PULSE_IN,
TIME_FROM_PTP_1588,
TIME_FROM_ROS_TIME
}"/>
実際に試してみたところトピック同士のずれは最大で150ms程度になるようです。仮に1m/s程度で歩きながら測定をしているとすると最大で150mmずれうることになるので、動いている最中にデータを取得するとずれが生じる可能性があります。今回はデータを取得するタイミングで一度静止するようにしながら測定を行いました。
保存したrosbagからはLiDARのオドメトリが得られますが、実際に得たい情報はカメラのオドメトリなので、位置関係から変換を行う必要があります。
今回はLiDARの上に両面テープでカメラを張り付け、カメラの位置はLiDARの6cm上にあるものとして変換を行いました。両面テープでは精度が気になりますが、今回の測定範囲の広さに対してここの位置関係はS/N比的に小さいだろうと考え、時間の兼ね合いもありこのようにしました。
変換を行う際は同次変換行列を使うと比較的シンプルな記述で実装できます。
得られるLiDARのオドメトリを\(\boldsymbol{T_\mathrm{wl}}\)とすると、回転行列を\(\boldsymbol{R_\mathrm{wl}}\)、並進ベクトルを\(\boldsymbol{t_\mathrm{wl}}\)として \[\boldsymbol{T_\mathrm{wl}}=\begin{bmatrix}\boldsymbol{R_\mathrm{wl}}
& \boldsymbol{t_\mathrm{wl}} \\ 0 & 1 \end{bmatrix} \tag{1}\]
で表します。これらの値は、今回だとSLAMから得られるオドメトリの値になります。
次に、同様にしてLiDARから見たカメラの姿勢を\(\boldsymbol{T_\mathrm{lc}}\)、回転行列を\(\boldsymbol{R_\mathrm{lc}}\)、並進ベクトルを\(\boldsymbol{t_\mathrm{lc}}\)として \[\boldsymbol{T_\mathrm{lc}}=\begin{bmatrix}\boldsymbol{R_\mathrm{lc}}
& \boldsymbol{t_\mathrm{lc}} \\ 0 & 1 \end{bmatrix} \tag{2}\]
と表します。これらの値はLiDARとカメラの位置関係から決まります。今回の例だと回転はなく、z方向に6cm(0.06m)ずらしてあげればよいので\(\boldsymbol{R_\mathrm{lc}}\)は単位行列、\(\boldsymbol{t_\mathrm{lc}}=[0, 0,
0.06]\)となります。
求めたいのは、元の座標でのカメラの姿勢です。求めたい回転行列を\(\boldsymbol{R_\mathrm{wc}}\)、並進ベクトル\(\boldsymbol{t_\mathrm{wc}}\)とします。先ほど示したLiDARのオドメトリと、LiDARから見たカメラの姿勢についての、回転行列と並進ベクトルの値を用いることで
\[\boldsymbol{R_\mathrm{wc}}=\boldsymbol{R_\mathrm{wl}}\boldsymbol{R_\mathrm{lc}},
\boldsymbol{t_\mathrm{wc}}=\boldsymbol{R_\mathrm{wl}}\boldsymbol{t_\mathrm{lc}}+\boldsymbol{t_\mathrm{wl}}
\tag{3}\] という風に求めることができます。
一方、先ほどの回転行列と並進ベクトルをまとめた同次変換行列(1)と(2)の積を取ると
\[\boldsymbol{T_\mathrm{wl}}\boldsymbol{T_\mathrm{lc}}=\begin{bmatrix}\boldsymbol{R_\mathrm{wl}}
& \boldsymbol{t_\mathrm{wl}} \\ 0 & 1
\end{bmatrix}\begin{bmatrix}\boldsymbol{R_\mathrm{lc}} & \boldsymbol{t_\mathrm{lc}}
\\ 0 & 1
\end{bmatrix}=\begin{bmatrix}\boldsymbol{R_\mathrm{wl}}\boldsymbol{R_\mathrm{lc}} &
\boldsymbol{R_\mathrm{wl}}\boldsymbol{t_\mathrm{lc}}+\boldsymbol{t_\mathrm{wl}} \\ 0 & 1
\end{bmatrix} \tag{4}\]
の関係が成り立ちます。(3)式と比較すると、同次変換行列の積を取ることで、求めたいカメラの姿勢を求めることができることがわかります。
FAST-LIOによって保存された点群情報に、色付けを行います。点群中のそれぞれの点について、取得したカメラ画像中に対応するものが存在するかを、カメラの推定した姿勢情報をもとにカメラ座標に変換を行うことで判定し、存在した場合そこに色を付けていきます。
具体的な処理内容について示していきます。
保存された点群の座標が、カメラの画像上でどこにあるかを把握するために、各カメラの姿勢ごとにワールド座標からカメラ座標に変換する際に必要な行列を計算します。
カメラ座標系からワールド座標系に変換する際に必要な回転行列を\(\boldsymbol{R_\mathrm{c2w}}\)、並進ベクトルを\(\boldsymbol{t_\mathrm{c2w}}\)とし、ワールド座標系からカメラ座標系に変換する際に必要な回転行列を\(\boldsymbol{R_\mathrm{w2c}}\)、並進ベクトルを\(\boldsymbol{t_\mathrm{w2c}}\)とします。これらの値を、ワールド座標におけるカメラの姿勢を表す回転行列\(\boldsymbol{R_\mathrm{wc}}\)、並進ベクトル\(\boldsymbol{t_\mathrm{wc}}\)が与えられた際にどう表せるかについて考えます。
回転行列から考えます。ここで、カメラ座標系のベクトルをワールド座標系に変換するための回転行列\(\boldsymbol{R_\mathrm{c2w}}\)はワールド座標からみたカメラの回転行列\(\boldsymbol{R_\mathrm{wc}}\)と捉えることができます。この行列の転置を取ることで、ワールド座標系のベクトルをカメラ座標に変換する行列\(\boldsymbol{R_\mathrm{w2c}}\)が得られます。 \[\boldsymbol{R_\mathrm{c2w}}=\boldsymbol{R_\mathrm{wc}},
\boldsymbol{R_\mathrm{w2c}}=\boldsymbol{R_\mathrm{c2w}^T}=\boldsymbol{R_\mathrm{wc}^T}
\tag{5}\]
次に並進ベクトルについて考えます。カメラ座標のベクトルをワールド座標に変換する際に用いられるベクトル\(\boldsymbol{t_\mathrm{c2w}}\)は、ワールド座標から見たカメラの並進ベクトル\(\boldsymbol{t_\mathrm{wc}}\)になります。 \[\boldsymbol{t_\mathrm{c2w}}=\boldsymbol{t_\mathrm{wc}}
\tag{6}\]
ワールド座標系からカメラ座標系に変換する際に用いるベクトル\(\boldsymbol{t_\mathrm{w2c}}\)は、ワールド座標系の点\(\boldsymbol{P_\mathrm{w}}\)をカメラ座標系\(\boldsymbol{P_\mathrm{c}}\)に変換する式の形を比較することでわかります。ワールド座標系の点\(\boldsymbol{P_\mathrm{w}}\)をカメラ座標系\(\boldsymbol{P_\mathrm{c}}\)に変換する式は \[\boldsymbol{P_\mathrm{c}}=\boldsymbol{R_\mathrm{w2c}}(\boldsymbol{P_\mathrm{w}}-\boldsymbol{t_\mathrm{c2w}})=\boldsymbol{R_\mathrm{w2c}}\boldsymbol{P_\mathrm{w}}-\boldsymbol{R_\mathrm{w2c}}\boldsymbol{t_\mathrm{c2w}}
\tag{7}\]
であることから、ワールド座標系からカメラ座標系に変換する際に用いるベクトル\(\boldsymbol{t_\mathrm{w2c}}\)は \[\boldsymbol{t_\mathrm{w2c}}=-\boldsymbol{R_\mathrm{w2c}}\boldsymbol{t_\mathrm{c2w}}
\tag{8}\] であるとわかります。(5)、(6)を用いることで \[\boldsymbol{t_\mathrm{w2c}}=-\boldsymbol{R_\mathrm{wc}^T}\boldsymbol{t_\mathrm{wc}}
\tag{9}\]
というように、与えられたカメラの姿勢を用いて求めることができることがわかります。
以上から、ワールド座標系からカメラ座標系に変換する際の変換は \[\boldsymbol{R_\mathrm{w2c}}=\boldsymbol{R_\mathrm{wc}^T},
\boldsymbol{t_\mathrm{w2c}}=-\boldsymbol{R_\mathrm{wc}^T}\boldsymbol{t_\mathrm{wc}}
\tag{10}\] を用いることで行えます。
これを用いて点群の各点の座標をカメラ座標に移します。ここで注意する必要があるのが、座標の対応です。カメラの座標系ではカメラが向いている方向がz軸でオドメトリで使っている座標とは扱いが異なります。今回の例ですと、オドメトリの座標は鉛直上向きをz軸としているので、オドメトリの\((x_\mathrm{odom},y_\mathrm{odom},z_\mathrm{odom})\)はカメラ座標でいうと\((z_\mathrm{cam}, x_\mathrm{cam},
y_\mathrm{cam})\)に対応するという具合になります。
対応する点に座標を変換したら、カメラ座標での点\((x_\mathrm{cam},y_\mathrm{cam},z_\mathrm{cam})\)と事前にキャリブレーションしたカメラの内部パラメータを合わせて正規化を行います。カメラの画像上の点\((u,v)\)は \[u=f_\mathrm{x}(x_\mathrm{cam}/z_\mathrm{cam})+c_\mathrm{x}
\tag{11}\] \[v=f_\mathrm{y}(y_\mathrm{cam}/z_\mathrm{cam})+c_\mathrm{y}
\tag{12}\]
となります。これが画像の画面内に入っていればその点の色情報を付加します。このままだとカメラの向いている同一直線状の点がすべて塗られてしまうので、カメラ座標でのz座標のバッファを持って置き、カメラから遠い点には色付けを行わないようにしています。
実際に測定した結果を示していきます。
まず、画像1枚からの測定を行ってみたところ、次のような色付きの点群が得られました。
1枚目の画像はUSBカメラで撮影された画像で、2枚目が得られたLiDARの点群全体、3枚目が得られた点群のうち色付けされたもののみを抜粋したものになります。
2枚目の画像から、LiDARで得られた点群のうち、画像に映っている部分(会議室の一部)のみが色付けされている様子がわかります。また、塗られた点群のみを表示した3枚目の画像から、撮影された画像に映っていたハンガーラックや空気清浄機といったものが、色のついた点群として再現されている様子が確認できます。
次に、LiDARとカメラを移動させながら、複数枚の画像について測定を行ってみました。椅子の周りを半周するようにカメラとLiDARを載せた台車を動かし、その途中で撮影された5枚の画像から色付きの点群を作成しました。
(撮影した画像について、社内の機材などが映っている箇所には加工が入れてあります。ご了承ください。)
1枚目から5枚目までの画像がカメラによって撮影した画像で、6枚目が取得した全体の点群、7枚目が色のついた点を抜粋した点群となります。
色が付けられた点群の様子から、椅子の背もたれや座面が確認できます。
一方で、全体の点群の画像から、部屋全体の形状が歪んでしまっていることもわかります。また、色付き点群の抜粋から、対象物が本来存在しない領域に点群が生成されてしまっていることもわかりました。
また、SLAMによる自己位置推定についても動かしているとずれが生じてしまうことがあることがわかりました。以下は2枚の画像について点群を生成したものの、自己位置推定がずれてしまった際の測定結果です。
1、2枚目がカメラで撮影された画像で、3枚目が色付けされた点群の抜粋です。
点群の画像を見ると、自己位置推定がずれていたために別の箇所の点に色付けをしてしまっており、本来1つのはずの空気清浄機や霧吹きが2つ存在しているようになってしまっていることがわかります。
これらの測定結果や、測定中に気付いたことから、現状の課題とその改善案の考察を、以下に示します。
現状、カメラとLiDARのデータの同期には最大で150ms程度のずれが生じています。これは同期を行うROSノードと、カメラの画像データやSLAMからの自己位置推定のデータを出力するROSノード間での通信に時間がかかることが要因の1つとして考えられます。
ROS2では、ノードを同一コンテナ内で起動することで1つのプロセスとして動作させることで、ノード間の通信を軽量・高速にするプロセス内通信という手法があります。今回用いているノードをコンテナ内で駆動するコンポーネントに対応するように実装を行うことで、性能の改善ができるのではないかと考えられます。
今回マッピングと自己位置推定にはSLAMを使用しましたが、SLAMは外部環境を測定しマッピングを行いながら、その特徴点のマッチングにより自己位置推定を同時に行います。この原理上、測定中に誤差が生じてしまいマッピングがずれてしまった場合、そのずれた情報で自己位置推定を行い、またマッピングをして、といった具合に進み誤差を打ち消すことができず、累積誤差として蓄積されてしまうという課題があります。今回の測定結果で示した複数枚での測定で地図が歪んでしまったことや、自己位置推定がずれてしまう要因の1つであると考えられます。
これの対策としては、ループ閉じ込みを行うことが挙げられます。ループ閉じ込みとは、測定を行って一度通った位置に戻ってきた際に、始点と終点を一致させる処理を行うことで累積誤差を減らすという手法です。
FAST-LIOにこの処理を実装する先行事例としては、FAST-LIO_SLAMや、FAST_LIO_LCが挙げられます。これらを用いて取得した地図と軌跡の情報を改善することで、測定結果の点群データと自己位置推定の誤差を減らすことができると考えられます。一方で、先行事例の実装はどちらもROS1のものなので、機能追加を行う際は対応させる作業が必要になると考えています。
また、測定の際に動く物体があると、それがSLAMのマッチングの際、誤差の要因となります。今回の測定で複数枚撮影した際に椅子の周囲に対象物ではない点群が生成されてしまいましたが、これは測定中に台車を押していた人間の身体を測定してしまったものと考えられます。測定の際に動く物体が入らないようにする必要があることがわかりました。
それぞれの測定で得られるIMUセンサの測定値に誤差が含まれることも、自己位置推定がずれる要因であると考えられます。特に加速度センサから得られる加速度はジャイロセンサから得られる角速度と比較して、変位の二階微分であることや、測定値に常に重力加速度がかかることから誤差が生じやすいです。今回の測定で各オドメトリの値を確認すると、角度方向に比べて並進方向の位置のずれのほうが大きくなる傾向が見られました。示した測定結果ですと2枚の画像から得たオドメトリが角度方向にはずれずに横にスライドするようにずれている様子から読み取れると思います。
これを改善するためには、IMUをOuster内蔵のものではなく、より精度の出せるものを外付けする案が考えられます。Ouster内蔵のIMUはICM-20948という型番のものが採用されており、加速度センサのノイズは230μg/√Hz、ジャイロセンサのノイズは0.015dps/√Hzとなっています。一方で、LiDARを用いた3DGSの先行事例で上げたLetsGoで用いている測定デバイスではXsens MTi-630という外付けのIMUが採用されています。こちらのノイズは加速度センサが60μg/√Hz、ジャイロセンサが0.007dps/√Hzとなっており、IMUの出力結果の信頼性を高めることができると考えられます。
また、LiDARで特徴点がうまくとらえられなかった際にカメラで補うために、LIVO(LiDAR-Inertial-Visual Odometry)を採用することも考えられます。しかし、要素が増えてシステムが複雑になることが考えられるので、まずはこれまでで示した改善案を試してから改良していくのが良いのではないかと考えています。
まとめると、LiDARを用いて測定を行う際は、SLAMでの自己位置推定やマッピングのずれが課題となることがわかりました。現状開発したシステムでは3DGSのデータとして使うことが難しいため、今後は上記で示した案で改善を行う必要があると考えられます。
この記事では、LiDARを用いた3D Gaussian Splatting向けのデータセット作成の取り組みについて紹介しました。手持ちのLiDARやUSBカメラを使用するとどういった実装になるのかや、測定においてどういったデータが取れるのかが分かりました。また、今後の改善案について考察しました。
インターンシップは15日間と限られた期間の中で、また、私自身LiDARや画像処理、SLAMなど初めてのことも多く試行錯誤する場面が多かったですが、周囲の方々に助言をいただきながらある程度形にすることができました。ありがとうございました。
Fixstars では、通年でインターンシップを募集しています。 高専生、大学生、大学院生の皆さん、Fixstars でのインターンシップで新しい技術に触れませんか? インターンシップの詳細は こちら をご覧ください。
keisuke.kimura in Livox Mid-360をROS1/ROS2で動かしてみた
Sorry for the delay in replying. I have done SLAM (FAST_LIO) with Livox MID360, but for various reasons I have not be...
Miya in ウエハースケールエンジン向けSimulated Annealingを複数タイルによる並列化で実装しました
作成されたプロファイラがとても良さそうです :) ぜひ詳細を書いていただきたいです!...
Deivaprakash in Livox Mid-360をROS1/ROS2で動かしてみた
Hey guys myself deiva from India currently i am working in this Livox MID360 and eager to knwo whether you have done the...
岩崎システム設計 岩崎 満 in Alveo U50で10G Ethernetを試してみる
仕事の都合で、検索を行い、御社サイトにたどりつきました。 内容は大変参考になりま...
Prabuddhi Wariyapperuma in Livox Mid-360をROS1/ROS2で動かしてみた
This issue was sorted....