WIT motion WT901C(RS232版)を動かすまでの手順_Ubuntu 20.04 ROS Noetic

memo

やろうとしていることの概要

Livox社のLiDAR「mid-70」でハンディレーザースキャナ的なものを作ろうとしている。別記事にて、LiDARの点群情報だけでSLAMを行う「livox_mapping」を動かすまでの手順について紹介したが、これは特徴的な形状がない(同じような形が続く)場所においてはうまく自己位置推定ができない場合がある。
そこで「livox_mapping」の次に、LiDARの点群情報とIMU(慣性計測装置・加速度や角速度などを計測できるセンサ)の姿勢情報をいい感じに組み合わせてSLAMをやってくれる、「FAST-LIO(Fast LiDAR-Inertial Odometry)」を試してみることにした。

本記事では、「FAST-LIO(Fast LiDAR-Inertial Odometry)」を動かす前提条件である、IMU(WIT motion社 WT901C RS232版)をROS Noeticで動かすまでに必要な手順についてまとめた。

なお、本記事で紹介するIMU(WIT motion社 WT901C RS232版)は、以下の点で優れている。
・センサ単体でカルマンフィルタのような処理が行われており、高精度な姿勢情報を取得できる
200Hzで姿勢情報を出力できる(※1)
・高性能な割に比較的安い(4000円程度)
・ROSで簡単に使える
・センサの筐体がイケてる(基板むき出しでない)、搭載しやすい形状である

一方で、いまいちだと感じた点は以下の通りである。
・同一型番・若干異なる型番で似たようなものがたくさんある(※2)
・WIT motion社が出している変換ケーブル(USB⇔RS232等)を購入すると若干高い(※3)
・ROSで使用する前に、WindowsのPCで設定が必要

筆者の検証の結果、最終的な目的である「FAST_LIO」と組み合わせて使用できることが確認できたため、とりあえずオススメである。

※1:WIT motion社の「WT901C」と同様に、ROSで使いやすいと評判のIMU「BNO055」というものもあり、2500円程度とより安価である。試してみたところ、(ちゃんと調べていないが)BNO055ではどうも50Hzまでしか出せないようで、「FAST_LIO」と組み合わせて使用するには不十分だった。

※2:WIT motion社の「WT901C」をAmazonで検索すると、「RS232版」「RS485版」「TTL版」の3種類がでてくる(そっくりな型番のものを含めると、見た目ほぼ同じものがたくさん出てくる)。それぞれ通信方式が異なり、互換性がないため、購入する際は注意が必要である。なお、筆者のオススメは「TTL版」である(※4)。

※3:「RS232版」「RS485版」「TTL版」それぞれに対応したケーブルがあるが、見た目が全く同じなので購入する際は注意が必要。なお、これら3種の通信方式すべてに対応したものも売られている。

※4:世の中には、「USBシリアル変換モジュール」がたくさん売られているが、「シリアル通信」と一言にいっても色々な通信プロトコルが含まれており、いまいちよくわからない。「RS232C」「UART」「TTL」当たりの通信プロトコル名が記載されていることが多いが、これらは電圧のレベルが違っていたりすることがままあるので要注意である。なお、本記事でおすすめの「TTL版」は、適当な安いUSBシリアル変換基板と組み合わせて使える(と思う)のでおすすめしている。間違っていたらごめん。

RS232版に、USB-TTL変換基板を使用して通信しようとしている図(当然うまくいかない)

前提条件

別記事にて示した、Ubuntu 20.04にROS Noeticを入れた状態から本記事の手順を実行した。また、ユーザー名はRaspberry PiのデフォルトであるPiとして各種操作を実行した事例を示すので、本記事を参考に同じ操作を実行する際は、ユーザー名やディレクトリ名については各自の環境に合わせて適宜読み替える必要がある点に注意が必要である。

また、本記事はWIT motion社 WT901C (RS232版)とPCが通信できていること、Windows用の公式ソフトでの出力設定ができていること(※)を確認の上実施されたい。

※:以下の参考ページの手順を参考に、ボーレートを115200bps、OutputRateを200Hzに設定する。
qiita.com/porizou1/items/0e9c956c89c584f6c072

インストール手順

以下のページを参考に、手順を検討した。
qiita.com/porizou1/items/0e9c956c89c584f6c072

WIT motionのセンサを使えるようにするためのコマンドは以下の通り。

sudo apt install ros-noetic-ecl*
cd ~/catkin_ws/src
git clone https://github.com/yowlings/wit_node.git
cd ~/catkin_ws
catkin_make

なお参考リンクにおいて、最後の「catkin_make」の部分は「catkin build」となっているが、catkin_makeでも問題なく処理が行えたことを確認している。というか、別記事の手順に沿ってROSやlivox_ros_driverなどのインストールを行っていた場合、「catkin build」すると怒られる(もっと言うと、catkin buildをインストールする必要がある)。
(【未検証】ここの手順については、もしかしたら「catkin_make –pkg wit_node」みたいな感じでやらないとうまく行かないこともあるかもしれない。)

動作確認

①Serial通信のポートの設定

最初に、IMU(WT901C+USBシリアル変換モジュール等)をPCに接続し、以下のコマンドを実行する。

ls -l /dev/serial/by-id/

実行すると、以下のように接続されているデバイスが表示される

lrwxrwxrwx 1 root root 13 6月 28 12:09 usb-1a86_USB2.0-Serial-if00-port0 -> ../../ttyUSB0

上述のコマンドで調べた名前のシリアルデバイスへのアクセス権限を付与するため、以下のコマンドを実行する。動作確認用プログラムを実行する前にこれをやらないと「Permission Denied」でエラーがでる。

sudo chmod 777 /dev/ttyUSB0

↑「ttyUSB0」の部分は、各自の環境に合わせて設定する(複数シリアル通信をするデバイスを接続している場合など、異なる名前が割り振られている場合がある。)

②動作確認

ターミナルを2つ開き、以下のコマンドをそれぞれのターミナルで実行する。

roslaunch wit_node wit.launch
rostopic echo /imu

実行結果の例は以下の通り。IMUを回してみることで、正しい値が取得できているかを確認することができる。

---
header: 
  seq: 189766
  stamp: 
    secs: 1698295858
    nsecs: 414137784
  frame_id: "imu_link"
orientation: 
  x: -0.7088912017574482
  y: -0.0368167956339868
  z: 0.049136853742948385
  w: 0.702640275841323
orientation_covariance: [0.001, 0.0, 0.0, 0.0, 0.001, 0.0, 0.0, 0.0, 0.001]
angular_velocity: 
  x: 0.0
  y: 0.0
  z: 0.0
angular_velocity_covariance: [1e-05, 0.0, 0.0, 0.0, 1e-05, 0.0, 0.0, 0.0, 1e-05]
linear_acceleration: 
  x: -0.18662109375000002
  y: -9.8
  z: -0.06699218750000001
linear_acceleration_covariance: [0.01, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.01]
---

以上。

コメント