2022年5月8日日曜日

LDS-006 LiDARをROSで使ってみた。

 この前購入した格安LiDAR、とりあえず動くところまでわかったので今度はROSで使えないかどうか調べてみた。

ROSで使えるLiDARで似たような形状しているやつだとRPLidarとか、同じようにUARTで通信しているタイプでLaserScanメッセージ対応のROSドライバベースで作れないかと、LiDARの仕様書や使い方のページとにらめっこして、近いプロトコルないかなーとか探してみた。

その過程で見つけたNeato XV-11っていう掃除ロボットに乗ってるLiDARがLDS-006のプロトコルにそっくりということを発見。

そっくりということは実は同じプロトコルでLDS-006の解析結果が間違っているんじゃないかという疑いが…
たしかに他のLiDAR用に作られたツールを改造してそこそこ使えそうな気はしていたんだけど、定期的に変なデータが来て値が飛んでいた。

そこで、解析してみるとLDS-006の距離データの部分に実はエラーフラグとエラーコードが含まれていたっぽい。これはXV-11の方のプロトコル解析結果を見てもしかしてと思って、距離のデータのHigh Byteの上位2ビット目を観察するようにしてみたら判明した。上位2ビットが0以外になると実は距離データのLow Byteがエラーコードになるようで、それが距離データとしては特定の角度で一定の変な値が出ることを確認。

というわけでLDS-006はXV-11のプロトコル互換ということで、XV-11がROS対応しているのをいいことにそのままXV-11用のドライバでROSで動かしてみた。
LDS-006にはモータ制御のコマンドが存在するのでモータ制御のコマンドは自分で実装するか手動で送信するしか無いけど。("startlds$"で回転、"stoplds$"で停止)

2.0mmピッチのコネクタも一応2.54mmピッチに変換して(4pinぐらいなら半田でなんとかなる)USB-Serial変換アダプタはCP2102搭載のものを使用した。

使用したドライバはxv_11_laser_driver
これはパッケージも提供されているようなのでapt-getでインストールできた。

あとはroscoreを動かしたあとに別なターミナルで

echo "startlds$" > /dev/ttyUSB0

をするとLDS-006が回り始める。
次に

rosrun xv_11_laser_driver neato_laser_publisher _port:=/dev/ttyUSB0 _firmware_version:=2 _frame_id:=laser

これでROSでLiDARのデータを解析してROSに渡してくれる。firmware versionはXV11のLiDARは通信プロトコルが2種類あるので2のほうがLDS-006と互換のほう。frame idはデフォルトでneato_laserになってるんだけど、laserにしたほうがRPLidarとかの使い方のサイトを参考にしたときにそのままコピペできるので便利だと思ってこのオプションを追加して変更した。

/dev/ttyUSB0は環境に合わせて変更。Permission Errorが出たので

sudo chmod a+rw /dev/ttyUSB0

してやった。適当だけど動いたので良し…(あとでちゃんとグループ調べて追加しないと…

あとはRVizを開いてFixed Frameにlaserって入れれば見れるはず。

LDS-006 ROS
データの取得ができた。やっぱりエラーフラグもちゃんと処理してるのか、動かしても変なデータが出ないのでいい感じ。
xv11が5mなので5mまでしか見ていないかもしれないけど、LDS-006がどのぐらい届くかは見てみないとなぁ
ちなみに分解能はやっぱり1°で、スキャン周波数は5Hzぐらいだった。
ROS対応でこのぐらいの性能なら1万円ぐらいの低価格帯のLiDARレベルかもしれない。

とりあえずRPLIDARと同等ぐらいにはROSで扱えそうな気がしてきたので、RPLIDARの情報を参考にSLAMとか試してみようかな。

0 件のコメント:

コメントを投稿