えいあーるれいの技術日記

ROS2やM5 Stack、Ubuntuについて書いています

RaspberryPi OSでVLP-16をROS2で動かす(RaspberryPi4)

執筆中の記事「RaspberryPi OSで始めるROS2(仮)」に追加される内容を先にブログに投稿しています。

最近TLでVelodyne Lidarの購入報告がたくさん上がっていますね。

最近はMID-360などの小型で広範囲スキャンしてくれるセンサも増えています。

低価格化に伴い、ご家庭の測定機器として一家に一台の時代が到来しているということでしょうか?


しかしながら、中古でも10万近くするLidarを買ってしまうと、それを処理するためのコンピュータ不足に悩まされてしまいますよね(!?)

ここでは、研究室に落ちていたVelodyne(VLP-16)をRaspberryPi OS + Raspbianで動かす方法について説明したいと思います。

Raspbianは、RaspberryPi向けに作成された軽量Linuxで、Rvizも軽快に動きます。


ここでは、VLP-16のソフトウェア側の構築方法を説明します。配線などは、説明書や他の記事を参考にしてください。

ほとんどの場合は、Jetson XavierやOrinやゲーミングPC上で環境構築をして動かした方が幸せになれます。


必要なもの

  • VLP-16
  • 変換コネクタ
  • RaspberryPi4 Model Bとその周辺機器
  • RaspberryPi OS (64bit) が書き込まれたSDカード


RaspberryPiの環境構築

ROS2のインストール

RaspberryPiではない場合、ROS2 Documentationを見ながら環境構築すれば大体解決します。

ここからのコマンドは、RaspberryPi OSの初期設定が終わった直後の状態を想定しています。

sudo apt update && sudo apt upgrade
sudo apt install -y libpcl-dev libyaml-cpp-dev libpcap-dev

wget https://s3.ap-northeast-1.wasabisys.com/download-raw/dpkg/ros2-desktop/debian/bullseye/ros-humble-desktop-0.3.1_arm64.deb
sudo apt install -y ./ros-humble-desktop-0.3.1_arm64.deb


ソースコードの取得

ros2_wsワークスペースとします。

依存関係を自力で解決しなければならないので、package.xmlを見ながらソースコードを追加していきます。

velodyne.gitを含む3つのパッケージで動くと思います。

mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src

git clone https://github.com/ros-drivers/velodyne.git -b ros2
git clone https://github.com/ros/angles.git -b ros2
git clone https://github.com/ros/diagnostics.git -b humble


ビルドします。

source /opt/ros/humble/setup.bash
cd ~/ros2_ws/
colcon build


IPアドレスの探索

Velodyneはデフォルトで10.0.0.201に設定されていますが、変更される場合もあります。その場合、外部からは見つからないため、wiresharkで探す必要があります。

sudo apt install -y wireshark
# 青画面が出た場合はyesを選択
sudo wireshark


Velodyneイーサネットに直接続している場合はeth0を選択する必要があります。

ここでは、192.168.0.200が見つかったので、dhcpcd.confを編集する必要があります。

sudo nano /etc/dhcpcd.conf
# 末尾に追記
interface eth0
static ip_address=192.168.0.100/24
static routers=192.168.0.1


編集したらCtrl+oで保存→Ctrl+xで終了して再起動します

ifconfigを実行してeth0欄で192.168.0.100となっていればOKです。

再起動しない場合は、sudo systemctl restart networking.service && sudo service dhcpcd reloadで読み込めると思います。

WebブラウザでVLP16のIPアドレス(ここでは192.168.0.200)にアクセスして設定が可能です。


VLP16の起動

ターミナル1

Velodyneのドライバです。デバイスIPアドレスとモデル名は適宜変更してください。

source ~/ros2_ws/install/setup.bash
ros2 run velodyne_driver velodyne_driver_node --ros-args -p device_ip:="192.168.0.200" -p model:="VLP16"


ターミナル2

ROS2のPCL2形式に変換するノードのようです。

source ~/ros2_ws/install/setup.bash
ros2 launch velodyne_pointcloud velodyne_convert_node-VLP16-launch.py


ターミナル3

最後に、可視化ツールRvizで開きます。

source ~/ros2_ws/install/setup.bash
rviz2
# frameをvelodyneに設定
# pointclound2を選択して/velodyne_pointsを開く


レンダリングしなければ、UDPでデータが流れてくるだけなので、それほど重くはなりません。

しかし、点群処理を行うには性能がかなり厳しいかもしれないので、工夫が必要です。


参考資料

https://velodynelidar.com/wp-content/uploads/2019/12/63-9243-Rev-E-VLP-16-User-Manual.pdf

https://qiita.com/akira-sasaki/items/dff6f7c4196884d6746f