Jetson Nano DevKit B01 + dual CSI cameraのROSドライバです。
このROSパッケージはJetson Nano DevKit B01に取り付けたCSI camera(1つまたは2つ)の画像をGStreamerまたはJetson Linux Multimedia API経由で取得し、ROSのsensor_msgs/Imageとして配信するためのものです。
launchファイルでgscam
を呼び出し、GStreamerまたはJetson Linux Multimedia APIを経由して
- 解像度とフレームレートの設定
- カメラのキャリブレーション
- 複数のCSIカメラ画像の取得・配信
を実現しています。
jetson_nano_csi_cam
を動かすためには本リポジトリとその依存関係にあるソフトウェアをダウンロードします。
gscam
の詳細については、ROS Wikiまたはros-drivers/gscam@GitHubを参照してください。
以下のソフトウェアがインストールされたNVIDIA Jetson Nano DevKit B01にSainSmart IMX219 Camera Module for NVIDIA Jetson Nano Board (160 Degree FoV)を2つ接続して動作確認をしています。
- GStreamer-1.0 または Jetson Linux Multimedia API(JetPackとともにインストールされます)
- ROS Melodic
- GStreamer-1.0をサポートした
gscam
このリポジトリをcatkin_ws
にダウンロードします。
cd ~/catkin_ws/src
git clone https://github.com/rt-net/jetson_nano_csi_cam_ros.git
まずはじめにgscam
に必要なgstreamer
の関連パッケージをインストールします。
sudo apt-get install gstreamer1.0-tools libgstreamer1.0-dev libgstreamer-plugins-base1.0-dev libgstreamer-plugins-good1.0-dev
gscam
をcatkin_ws
にダウンロードします。
cd ~/catkin_ws/src
git clone https://github.com/ros-drivers/gscam.git
ダウンロード後、./gscam/Makefile
を編集してCMakeのオプションを変更します。以下のように-DGSTREAMER_VERSION_1_x=On
を追加します。
EXTRA_CMAKE_FLAGS = -DUSE_ROSBUILD:BOOL=1 -DGSTREAMER_VERSION_1_x=On
ダウンロードしてきたgscam
ディレクトリ内で以下のコマンドを実行すると簡単に編集できます。
sed -e "s/EXTRA_CMAKE_FLAGS = -DUSE_ROSBUILD:BOOL=1$/EXTRA_CMAKE_FLAGS = -DUSE_ROSBUILD:BOOL=1 -DGSTREAMER_VERSION_1_x=On/" -i Makefile
jetson_nano_csi_cam
とgscam
をビルドしセットアップします。
cd ~/catkin_ws
catkin build
source devel/setup.bash
CAM0として接続されたカメラストリームのデータを/csi_cam_0/image_raw
のROSトピックとして配信するには以下のコマンドを端末で実行します。
roslaunch jetson_nano_csi_cam jetson_csi_cam.launch sensor_id:=0 width:=<image width> height:=<image height> fps:=<desired framerate>
CAM0とCAM1に接続されたカメラストリームのデータをそれぞれ/csi_cam_0/image_raw
と/csi_cam_1/image_raw
のROSトピックとして同時に配信するには以下のコマンドを実行します。
roslaunch jetson_nano_csi_cam jetson_dual_csi_cam.launch width:=<image width> height:=<image height> fps:=<desired framerate>
ROSトピックとしてカメラの映像を配信するには以下のコマンドを実行します。
roslaunch jetson_csi_cam jetson_csi_cam.launch
このlaunchでは配信用のノードを起動するだけです。配信されている映像を確認するには何かしら別の手段を利用します。
映像が配信されているかを簡単に確認するには、端末を起動してrostopic list
を実行し、配信中のROSトピック一覧から/csi_cam_0/image_raw
という名前のトピックを探します。
roslaunch
する際のオプションで映像配信のパラメータを決めることができます。
roslaunch jetson_csi_cam jetson_csi_cam.launch width:=1920 height:=1080 fps:=15
その他の引数についてはroslaunch
の際に<arg_name>:=<arg_value>
形式でオプションを指定できます。
sensor_id
(default:0
) -- カメラのIDwidth
(default:640
) -- 配信する映像の横幅height
(default:480
) -- 配信する映像の高さfps
(default:30
) -- 配信するフレームレート(解像度次第ではこのフレームレートに満たない場合があります)cam_name
(default:csi_cam_$(arg sensor_id)
) --camera info
に対応したカメラ名frame_id
(default:/$(arg cam_name)_link
) -- tfに使用するカメラのフレーム名sync_sink
(default:true
) -- appsinkを同期設定(フレームレートを低く設定して問題が起きたときにこのオプションをfalse
にすると、問題が解決する場合があります)flip_method
(default:0
) -- 映像配信する際の画像の反転オプション
簡単にカメラ映像を確認するには、GNOME等のデスクトップ環境で端末を起動してrqt_img_view
を実行します。
起動した画像ビューアの左上のプルダウンメニューからカメラ映像のトピックを選択します。
jetson_csi_cam.launch
のデフォルト設定の場合は/csi_cam_0/image_raw
です。
次のコマンドでROSトピックの更新頻度を確認できます。
rostopic hz /csi_cam_0/image_raw
カメラ映像のROSトピックの更新頻度 == 配信されている映像のフレームレートではありませんが、ほぼ一致します。 設定したフレームレートよりも低い場合は以下の原因が考えられます。
- Jetson NanoのPowerManagementがパフォーマンスを制限するモードになっている
- Jetson Nanoと映像を受信しているコンピュータ間のネットワークが不安定
- 接続しているカメラモジュールの最大フレームレート以上の値を指定した
jetson_nano_csi_cam
はカメラのキャリブレーションを簡単にできるようにカメラ情報もROSトピックとして配信しています。
カメラ情報を実際に使用しているカメラに合わせるにはROS Wikiのmonocular camera calibration guideに従ってキャリブレーションしてください。キャリブレーションをしなくてもカメラ映像の配信は可能です。
その際、以下の情報を参考にしてください。
-
ROS Wikiの説明にあるようにチェッカーボードの印刷が必要です。
-
映像配信にて説明した
roslaunch
コマンドでカメラの映像配信をします。 -
image
とcamera
オプションとチェッカーボードのサイズを以下のコマンドのように指定し、キャリブレーションを行います。
rosrun camera_calibration cameracalibrator.py --size 8x6 --square <square size in meters> image:=/csi_cam_0/image_raw camera:=/csi_cam_0
カメラに映る範囲内である程度チェッカーボードを動かすと「CALIBRATE」ボタンが押せるようになるので、キャリブレーションファイルを書き出します。
(C) 2020 RT Corporation
各ファイルはライセンスがファイル中に明記されている場合、そのライセンスに従います。特に明記されていない場合は、Apache License, Version 2.0に基づき公開されています。
ライセンスの全文はLICENSEまたはapache.org/licenses/LICENSE-2.0から確認できます。
- peter-moran/jetson_csi_cam
- Copyright (c) 2017 Peter Moran
- MIT License
- https://github.com/peter-moran/jetson_csi_cam/blob/b4d839bdfca0e2714103c1d2fe3750f3a8f36832/LICENSE