🐕

【チュートリアル】GLIM + Livox MID360 + Jetson Orin Nano でLiDAR-IMU SLAM

2024/08/23に公開

SLAMチュートリアル

GLIMの紹介を兼ねて、Livox MID360Jeson Orin Nanoを使ったSLAMシステムの構築チュートリアルを書いてみます。

こういった動きに頑強な移動量推定&環境地図ができます。

2024/08/26 : Componentsとパラメータ調整を追記

前提条件

  • Jetson Orin Nano に Jetpack 6.0 がインストール済み
  • ROS2 humble がインストール済み (インストール手順)
  • Livox MID360が通電済み

Livoxの電源はどこからとっても良いですが、私はLivoxの純正ケーブルに12V USB PDトリガーケーブルをくっつけた以下のようなものを使用しています。急速充電器やモバイルバッテリーから電源を取れるのでとても便利です。

ネットワーク設定

JetsonとLivoxを接続するためのネットワーク設定を行います。JetsonにLivoxのイーサネットを直つなぎして、JetsonのIPをマニュアルで 192.168.1.5、ネットマスクを 255.255.255.0 に設定します。

Livox側のデフォルトIPアドレスはシリアル番号の下二桁が XX として、192.168.1.1XX になります。下の写真のものであれば、シリアルが ....282 なので、LivoxのIPは 192.168.1.182 です。

ネットワーク設定ができたら試しにLivoxに通電して ping 192.168.1.1XX を実行してみましょう。うまくLivoxと接続ができていれば以下のように応答が返ってきます。

koide@ubuntu:~/ros2_ws/src/livox_ros_driver2/config$ ping 192.168.1.182
# PING 192.168.1.182 (192.168.1.182) 56(84) bytes of data.
# 64 bytes from 192.168.1.182: icmp_seq=1 ttl=255 time=0.750 ms
# 64 bytes from 192.168.1.182: icmp_seq=2 ttl=255 time=1.31 ms
# 64 bytes from 192.168.1.182: icmp_seq=3 ttl=255 time=1.74 ms

Livoxドライバ セットアップ

Livox SDK2

Livox MID360用のSDKをインストールします。特に難しいところは無く、以下のコマンドを順に打ち込むだけです。

git clone https://github.com/Livox-SDK/Livox-SDK2.git
cd ./Livox-SDK2/
mkdir build
cd build
cmake .. && make -j4
sudo make install

ROS2ドライバ (livox_ros_driver2)

MID360のデータをROS形式で取り込むためのドライバをインストールします。

# ROS環境設定の読み込み
source /opt/ros/humble/setup.bash

# ROSワークスペースの作成
mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
git clone https://github.com/Livox-SDK/livox_ros_driver2.git
mv livox_ros_driver2/package_ROS2.xml livox_ros_driver2/package.xml

# ビルド
cd ..
colcon build --cmake-args -DROS_EDITION="ROS2" -DHUMBLE_ROS="humble" --symlink-install

ビルドが完了したらLivoxドライバの接続設定を行います。エディタで livox_ros_driver2/config/MID360_config.json を開いて、下部にある "lidar_configs/ip" を先程確かめたLivoxのIPアドレス(192.168.1.1XX)に変更します。

本来はJetson側のIPも変更する必要が有りますが、今回はJetsonのIPをデフォルト設定と同じ 192.168.1.5 にあらかじめ設定しているので変更は不要です。

cd ~/ros2_ws/src/livox_ros_driver2/config
nano MID360_config.json
# "host_net_info" : (変更前)"192.168.1.5"  -> JetsonのIP(今回は変更しなくて良い)
# "lidar_configs/ip" : (変更前)"192.168.1.12"  -> LivoxのIP("192.168.1.1XX")

接続テスト

ここまで来たらLivox ROSドライバを立ち上げて点群を確認してみましょう。以下のようにコマンドを入力すればROSドライバとrvizが立ち上がり点群が表示されるはずです。ひとしきり確認できたらrvizは重たいので閉じておきましょう。

source ~/ros2_ws/install/setup.bash
ros2 launch livox_ros_driver2 rviz_MID360_launch.py

GLIM セットアップ

今回はビルド済みのパッケージをPPAからインストールします。

インストール

最初に必要なツール・ライブラリをインストールします。

sudo apt update
sudo apt install -y gpg curl libiridescence-dev libboost-all-dev libglfw3-dev libmetis-dev

その後、以下のコマンドでPPAの登録と glim_ros2 (CUDA 12.5) をインストールします。インストール後に sudo ldconfig を実行して共有ライブラリがシステムから見えるようにしておきます。

# PPAを登録
curl -s https://koide3.github.io/ppa/setup_ppa.sh | sudo bash

# glim_ros2 (CUDA 12.5) をインストール
sudo apt update
sudo apt install -y ros-humble-glim-ros-cuda12.5
sudo ldconfig

パラメータ設定

GLIMのパラメータ設定を行うため、まずインストールしたパッケージからパラメータの雛形をコピーします。

# パラメータの雛形を手元にコピー
cp -R /opt/ros/humble/share/glim/config ~/.

設定ファイルの重力加速度スケールと点群・IMUトピック名を以下のように変更します。

# パラメータを変更
nano ~/config/config_ros.json
# "acc_scale": 9.81
# "imu_topic" : "/livox/imu"
# "points_topic" : "/livox/lidar"

動かしてみる

実際にGLIMを動かしてみましょう。GLIMの起動は ros2 run glim_ros glim_rosnode で行います。設定したパラメータを読み込むために、以下のように --ros-args -p config_path:=configの絶対パス としてコンフィグの場所を指定します。

source /opt/ros/humble/setup.bash
ros2 run glim_ros glim_rosnode --ros-args -p config_path:=$(realpath ~/config)

うまく動作していれば以下のようにビューワが表示され、センサの自己位置推定と周囲地図生成が行われている様子を見ることができます。

いじめてみる

GLIMではLiDAR-IMUタイトカップリングとウィンドウ最適化という、急激な動きや瞬間的なデータ欠損に強いアルゴリズムを実装しています。振り回したり一瞬であれば目隠ししてもなかなか破綻しないので遊んでみてください(やりすぎると流石にクラッシュします)。

外で試してみる

MID360は安価な割に計測可能範囲が広いので車に載せて簡便な車両自己位置推定などもできます(画像クリックでYoutubeへ)。

orinnano

もうひと手間

通信負荷の軽減 (Components)

ここまでで一応動作しているけれど時々表示がカクつくという状況になっているかもしれません。これはROS2のDDSの通信性能が悪く、同一PC内であっても点群のような容量の大きいデータやIMUのような高周期のデータをやり取りするとデータがドロップしてしまうためです。

通信負荷を軽減するための仕組みとしてROS2にはコンポーネントというがあります。これは一つのプロセス内で複数のノードを起動することで、高速なプロセス内通信を利用できるようになるというものです。

使用するにはまず、コンポーネントを束ねるコンポーネントマネージャを起動します。コンポーネントマネージャはデフォルトでは /ComponentManager という名前がつけられて起動します。

ros2 run rclcpp_components component_container  # マネージャが立ち上がり、 /ComponentManager という名前がつけられる

その後、livoxドライバとGLIMのコンポーネントをそれぞれマネージャに読み込みます。読み込みコマンドは ros2 component load マネージャ名 パッケージ名 コンポーネント名 パラメータ となっており、今回は以下のように順に入力します(Livoxの設定ファイルのパスは適宜修正してください)。

ros2 component load /ComponentManager livox_ros_driver2 livox_ros::DriverNode -p user_config_path:=/home/koide/ros2_ws/src/livox_ros_driver2/config/MID360_config.json
ros2 component load /ComponentManager glim_ros glim::GlimROS -p config_path:=$(realpath config)

読み込みがうまく出来ていれば通常起動時と同様にGLIMのビューワが立ち上がります。また、ros2 component list によって立ち上がっているマネージャと読み込まれているコンポーネントを確認することができます。

ros2 component list

# /ComponentManager
#   1 /livox_driver_node
#   2 /glim_ros

パラメータ調整

GLIMはなるべく繊細なパラメータ調整をしなくても動作するように設計されていますが、環境に応じてパラメータを微調整してやるとさらに精度・頑強性を増すことができます。

詳細はドキュメントの重要なパラメータリストを参考にすると良いですが、ここでは特に重要なパラメータを紹介します。

点群前処理 (config_preprocess.json)

  • random_downsample_target : 点群のダウンサンプリング後の目標点数です。これを下げることで処理負荷を大きく減らすことができます。デフォルト設定は10000点ですが、5000点程度までは減らしてもそれほど精度劣化は起きません。

オドメトリ推定 (config_odometry_gpu.json)

  • voxel_resolution : 対応付け探索に用いるボクセルマップの解像度です。屋内では小さめ (0.25 ~ 0.5 m)、屋外では大きめ (0.5 ~ 1.0 m) に設定します。サブマップ最適化、大域最適化用のボクセルマップ解像度 (config_sub_mapping_gpu.json & config_global_mapping_gpu.json) も同様に屋内では 0.5 ~ 1.0 m、屋外では 1.0 ~ 2.0 m に設定すると良いです。

大域最適化 (config_global_mapping_gpu.json)

  • min_implicit_loop_overlap : サブマップ間の重なり率のしきい値で、重なりがこの数値より大きい全てのサブマップ間にマッチングコスト制約が生成されます。小さい値 (e.g., 0.05) を設定すると大域最適化グラフがより高密度になり、精度が上がりますが処理負荷とメモリ消費が増えます。
    反対に大きい値 (e.g., 0.4) を設定すると、処理負荷とメモリ消費が下がる代わりにループクローズ性能が低下します。

Discussion