- 概要 ①格安ドローンTello×ORB-SLAM3×ROS-noeticでVisual-SLAM自律飛行する
- とりあえずROSでドローンを飛ばす ②格安ドローンTelloをROS1-noeticで飛ばす
- Visual-SLAMとしてORB-SLAM3を導入 ③ubuntu20.04にORB-SLAM3を導入する ←本記事
- Visual-SLAMでナビゲーション
目次
ORB-SLAM3について
ORB-SLAM3はスペインのサラゴサ大学のRaúl Mur Artal氏のチームが開発したORB-SLAMアルゴリズムを用いたSLAMソフトウェアの最新バージョンです。
ORB-SLAM自体は2014年に発表されたアルゴリズムなんですが、なかなか優秀で有名なので未だに研究畑でも用いられていたりするらしいです。
SLAMソフトウェアとして、ORB-SLAM3は2をもとに開発されているわけですが、さらなる性能向上が行われていたり、IMUとの情報統合ができていたりとスマホAR向きの拡張がされているようです。
ORB-SLAM3は、
- 単眼カメラ
- ステレオカメラ
- RGB-Dカメラ
- 魚眼レンズカメラ
とそれぞれのIMU統合に対応しています。
今回のドローンでは単眼カメラでのVisual-SLAMを行います。
Pangolinのインストール
PangolinというGUI用のライブラリが必要だそうです。
入れます。
mkdir ~/soiya
cd ~/soiya
git clone https://github.com/stevenlovegrove/Pangolin.git
cd Pangolin
./scripts/install_prerequisites.sh recommended
cmake -B build
cmake --build build ←これは10分弱かかります。
Pangolin公式によると「masterブランチはちょくちょく崩壊してるよ、stableタグのやつを使ってね。」とのことです。
僕の環境だとmasterのコミット aff6883c83f3fd7e8268a9715e84266c42e2efe3 のやつは一発でビルド通りました。
Eigenのインストール
入れます。
https://gitlab.com/libeigen/eigen/-/releases/3.4.0
ここのSource code (zip)をダウンロードして適当な場所に展開
cd eigen-3.4.0/
mkdir build
cd build
cmake ..
sudo make install
ORB-SLAM3のインストール
ORB-SLAM3を適当なディレクトリにクローンし、ビルドします。
git clone https://github.com/UZ-SLAMLab/ORB_SLAM3.git
cd ORB_SLAM2
chmod +x build.sh
./build.sh ←これも10分弱かかります。
おそらく一発でビルドは通らないと思います。
幸いORB-SLAMは先人たちの礎が比較的豊富なので根気よく調べればだいたい解決します。
基本的にはORB-SLAM2とORB-SLAM3のissueを漁って、そこで出てきた情報をさらにネットで調べていく感じでなんとかなりました。
この記事の執筆にあたってOSのインストールからやりましたが(2022/9/14)、そのときに出てきたエラーと対処法を以下に載せます。
遭遇エラー①
CMake Warning at CMakeLists.txt:33 (find_package):
Could not find a configuration file for package "OpenCV" that is compatible
with requested version "4.4".
The following configuration files were considered but not accepted:
/usr/lib/x86_64-linux-gnu/cmake/opencv4/OpenCVConfig.cmake, version: 4.2.0
/lib/x86_64-linux-gnu/cmake/opencv4/OpenCVConfig.cmake, version: 4.2.0
CMake Error at CMakeLists.txt:35 (message):
OpenCV > 4.4 not found.
-- Configuring incomplete, errors occurred!
See also "/home/handaru/ORB_SLAM3/build/CMakeFiles/CMakeOutput.log".
make: *** ターゲットが指定されておらず, makefile も見つかりません. 中止.
解決法
OpenCVコンパチじゃないよエラー。ROS-kinetic以降でORB-SLAMを使っている記事があんまり見つからないのですが、公式gitのORB-SLAM2に同様のissueがあるので参考にして直しました。
多くの場合はOpenCVのバージョンがROS用で入ってるやつとマッチしていないせいだと思います。
コンパチなCVを入れてやってもいいんですが、ちょっと違っても割と動くので以下のようにcmake側で修正します。
/ORB-SLAM3/CMakeLists.txtの33行目以下にある4.4とかの部分を自分の環境のバージョンを調べて同じものに書き換えます。
find_package(OpenCV 4.2)
if(NOT OpenCV_FOUND)
message(FATAL_ERROR "OpenCV > 4.2 not found.")
endif()
遭遇エラー②
こんなのとか
/home/handaru/Pangolin/components/pango_core/include/sigslot/signal.hpp:1180:65: error: ‘slots_reference’ was not declared in this scope
1180 | cow_copy_type<list_type, Lockable> ref = slots_reference();
| ~~~~~~~~~~~~~~~^~
こんなのが大量に出る
/home/handaru/Pangolin/components/pango_core/include/sigslot/signal.hpp: In member function ‘size_t sigslot::signal_base< <template-parameter-1-1>, <template-parameter-1-2> >::disconnect(sigslot::group_id)’:
/home/handaru/Pangolin/components/pango_core/include/sigslot/signal.hpp:1439:46: error: ‘m_slots’ was not declared in this scope
1439 | for (auto &group : detail::cow_write(m_slots)) {
解決法
Pangolinと環境でc++11とc++14で異なることが原因です。
なので対応としてもPangolin側を戻すか、コンパイラを進めるかで2通りあります。
どちらかといえば楽なので、コンパイラのバージョンを変えることをおすすめします。
./build.shする前にターミナルに以下を入力するだけです。
sed -i 's/++11/++14/g' CMakeLists.txt
./build.sh
ORB-SLAM3付属のROSラッパーのビルド
ORB-SLAM3に内包されているROS用パッケージをビルドします。
普段catkin_wsだけモミモミしてしている方は慣れない感じがするかもしれませんが、ORB-SLAMはROSをwrapperとして、あくまでオマケみたいな感じで対応させているのでこんな感じになっています。ということで、実はROSからORB-SLAMにできることは起動と終了ぐらいです。これを自己位置推定に使う方法は後述します。
ちなみに、最近ではROS用パッケージがORB-SLAM3内のExampleディレクトリからExample_oldディレクトリに格下げされてしましました。
ということでExampleディレクトリへコピーして一軍に復活させるところからやる必要があります。
cd ~/ORB-SLAM3
cp -r Examples_old/ROS/ Examples
ここで、以下の文を~/.bashrcの最後尾に追記しておきます。ROSにORB-SLAM3の場所を教えるやつです。
PATHの部分は適宜自分の環境のパスに書き換えてください。
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:PATH/ORB_SLAM3/Examples/ROS
加えて、多分出ると思うので先に書いておきますが、先程のCV2のバージョンエラーと同様にROSのCMakeListsも書き換える必要があります。
ORB-SLAM3/Examples/ROS/ORB_SLAM3/CMakeLists.txtの33行目を任意のバージョンに書き換えてください。
できたらビルドします。
sudo chmod +x ./build_ros.sh
./build_ros.sh
これも一発では行かないかもです。
自分もエラーが出たので書いておきます。
遭遇エラー③
さっきのm_slotsとかのPangolinエラー。
解決法
さっきと同じでコンパイラのバージョン違いが原因なんですが、先程のやつが効いてないみたいなので直接書きます。
ORB-SLAM3/Examples/ROS/ORB_SLAM3/CMakeLists.txtの18行目
CHECK_CXX_COMPILER_FLAG(“-std=c++0x” COMPILER_SUPPORTS_CXX0X)の下辺りに以下の文字列をコピペしてビルドします。
add_compile_options(-std=c++14)
遭遇したエラー④
error: conversion from ‘Eigen::Vector3f’ {aka ‘Eigen::Matrix<float, 3, 1>’} to non-scalar type ‘cv::Mat’ requested
530 | cv::Mat Xw = pMP->GetWorldPos();
解決法
エラーが出ているcppファイルのヘッダーに以下のヘッダーファイルを追加します。
とりあえずORB-SLAM3/Examples/ROS/ORB_SLAM3/src下のcppに全部追加してもいいと思います。
#include "../../../include/Converter.h"
遭遇したエラー⑤
/home/handaru/ORB_SLAM3/Examples/ROS/ORB_SLAM3/src/AR/ros_mono_ar.cc:150:41: error: conversion from ‘Sophus::SE3f’ {aka ‘Sophus::SE3<float>’} to non-scalar type ‘cv::Mat’ requested
150 | cv::Mat Tcw = mpSLAM->TrackMonocular(cv_ptr->image, cv_ptr->header.stamp.toSec());
解決法
ros_mono_ar.ccのヘッダーに以下のヘッダーファイルを追加
#include <Eigen/Dense>
#include <opencv2/core/eigen.hpp>
続いて、同じくros_mono_ar.ccの151行目付近にある以下の行をコメントアウト
cv::Mat Tcw = mpSLAM->TrackMonocular(cv_ptr->image, cv_ptr->header.stamp.toSec());
そしてコメントアウトした行を以下の4行に置き換えます。
cv::Mat Tcw;
Sophus::SE3f Tcw_SE3f = mpSLAM->TrackMonocular(cv_ptr->image, cv_ptr->header.stamp.toSec());
Eigen::Matrix4f Tcw_Matrix = Tcw_SE3f.matrix();
cv::eigen2cv(Tcw_Matrix, Tcw);
遭遇したエラーその⑥
/home/handaru/ORB_SLAM3/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc: In member function ‘ORB_SLAM3::Plane* ORB_SLAM3::ViewerAR::DetectPlane(cv::Mat, const std::vector<ORB_SLAM3::MapPoint*>&, int)’:
/home/handaru/ORB_SLAM3/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc:424:57: error: no matching function for call to ‘std::vector<cv::Mat>::push_back(Eigen::Vector3f)’
424 | vPoints.push_back(pMP->GetWorldPos());
解決法
ViewerAR.ccのヘッダーに以下のヘッダファイルをインクルード
#include <Eigen/Dense>
#include <opencv2/core/eigen.hpp>
おなじくViewerAR.ccの405行目付近にある以下の行をコメントアウト
vPoints.push_back(pMP->GetWorldPos());
以下の文字列に置き換えます。
cv::Mat WorldPos;
cv::eigen2cv(pMP->GetWorldPos(), WorldPos);
vPoints.push_back(WorldPos);
遭遇したエラーその⑦
home/handaru/ORB_SLAM3/Examples/ROS/ORB_SLAM3/src/AR/ViewerAR.cc:554:46: error: conversion from ‘Eigen::Vector3f’ {aka ‘Eigen::Matrix<float, 3, 1>’} to non-scalar type ‘cv::Mat’ requested
554 | cv::Mat Xw = pMP->GetWorldPos();
解決法
ViewerAR.ccの552行目付近の以下の行をコメントアウト
cv::Mat Xw = pMP->GetWorldPos();
コメントアウトした行と以下の2行を入れ替える
cv::Mat Xw;
cv::eigen2cv(pMP->GetWorldPos(), Xw);
ORB-SLAM3の実行
ビルドが通ったらROSからORB-SLAM3を実行します。
とりあえずwebカメラでSLAMしてみます。webカメ使わずに試したいって人のためにカメラ映像のテストデータを配布しておきます。
Link to rosbag file of camera footage taken outdoors https://drive.google.com/file/d/16LbhS6u2HVhF-ft-1_DhfHLLshQ9nC61/view?usp=sharing
ROSでwebカメラを使うためのパッケージをインストール
sudo apt install ros-noetic-usb-cam
sudo apt install ros-noetic-rqt-image-view
USBでカメラをつないでデバイス名を調べる
ls /dev/video*
以下のコマンドでカメラ映像をトピックで配信、rqtで確認。合わせてトピック名も確認しましょう。多分/usb_cam/image_rawとかになっていると思います。
rosrun usb_cam usb_cam_node _video_device:=/dev/video0
rqt_image_view
ORB-SLAM3を起動
rosrun ORB_SLAM3 Mono Vocabulary/ORBvoc.txt Examples/Monocular/TUM1.yaml /camera/image_raw:=/usb_cam/image_raw
/camera/image_raw:= で入力映像のトピック名をリマップします。
起動すると画面が2つ出てきて、カメラをある程度動かしてやるとSLAMが起動します。
デフォルトのパラメータでも結構しっかり自己位置推定してくれます。カメラが動いても追従しますが、急峻な動きをするとlostすることがわかります。
次回はドローンのカメラでORB-SLAMを動かし、自己位置情報を取り扱う方法について解説します。
- 概要 ①格安ドローンTello×ORB-SLAM3×ROS-noeticでVisual-SLAM自律飛行する
- とりあえずROSでドローンを飛ばす ②格安ドローンTelloをROS1-noeticで飛ばす
- Visual-SLAMとしてORB-SLAM3を導入 ③ubuntu20.04にORB-SLAM3を導入する ←本記事
- Visual-SLAMでナビゲーション
コメント