1.1. ADLINK ROSCube RQX-58G 用 TIER IV カメラ スタート ガイド#
注意
このドキュメントはADLINK RQX-58Gのユーザー向けです。
1.1.1. 準備#
1.1.1.1. 機材#
ADLINK ROSCube-X RQX-58G
JetPack4.5 (L4T 32.5.1) または JetPack4.6 (L4T 32.6.1)
GMSL2 同軸ケーブル (FAKRA - mini FAKRA、1:4)
TIER IV 車載 HDR カメラ C1 または C2
1.1.1.2. カメラの接続#
まず、ROSCube-X の電源がオフになっていることを確認します。
カメラをケーブルの FAKRA コネクタ (シングル FAKRA コネクタ側) に接続します。次に、ケーブルのミニ FAKRA コネクタを ROSCube-X の GMSL2 ポートに挿入します。
FAKRA コネクタおよびミニ FAKRA コネクタのロックの方向が正しいことを確認してください (図 1 ~ 3)。
1.1.2. 電源投入とカメラからの画像出力の確認#
1.1.2.1. 電源投入#
ROSCube-Xの電源を入れ、パワーオンLEDが青色に点灯することを確認します。
1.1.2.2. ログイン#
起動ウィンドウで、パスワードを入力してログインします。
デフォルトの設定は以下のとおりです。
ユーザー |
ros |
パスワード |
adlinkros |
1.1.2.3. カメラドライバーのインストール#
注釈
C2を使用する場合、カメラドライバv1.4.1以上が必須です。必要な場合ドライバをアップデートしてください。
必要なカメラドライバーがすでにインストールされている場合は、このセクションをスキップしてください。
Github から カメラドライバ deb パッケージ を入手します。最新リリースはRQX-58Gで動作することが確認されています。
提供されたドライバー パッケージ ファイル (tier4-isx021-gmsl_*.*.*_arm64.deb
) を ROSCube-X 内の任意のディレクトリ (例: ~/c1_driver
) にコピーします。次に、以下の操作をコマンドラインで行います。
apt update
でパッケージを更新します。インターネット接続が必要です。次に、apt install
コマンドを使用してドライバーをインストールします。*.dtbo
ファイルが/boot
に生成されていることを確認してください。# Install sudo apt update sudo apt install make debhelper dkms sudo apt install ~/c1_driver/tier4-camera-gmsl_1.2.1_arm64.deb # Confirm /boot/tier4-*.dtbo exists ls /boot/*.dtbo
デバイスツリーオーバーレイのコマンドは、L4T バージョンによって異なります。 L4T バージョンを確認するには、
$ cat /etc/nv_tegra_release
を実行して結果を確認します。たとえば、# R32 (release), REVISION: 5.1...,
が返された場合、インストールされている L4T バージョンは「32.5.1」です。インストールされている L4T バージョンに応じた手順を選択してください。また、各ポートにカメラを割り当てるには、カメラ ドライバーの README ページ を参照してください。実現したいカメラの割当に応じて適切なオーバーレイ コマンドを指定して下さい。
# For L4T 32.5.1 sudo /opt/nvidia/jetson-io/config-by-hardware.py -n "TIERIV ISX021 GMSL2 Camera Device Tree Overlay" # Confirm /boot/kernel_tegra194-rqx-58g-tier4-isx021-gmsl2-camera-device-tree-overlay-roscube-r32_x.dtb has been generated ls /boot/kernel_tegra194-rqx-58g-tier4-isx021-gmsl2-camera-device-tree-overlay*.dtb # Then, shutdown the system sudo shutdown -h now
# For L4T 32.6.1 sudo /opt/nvidia/jetson-io/config-by-hardware.py -n 2="TIERIV ISX021 GMSL2 Camera Device Tree Overlay" # Confirm /boot/kernel_tegra194-rqx-58g-user-custom.dtb has been generated ls /boot/kernel_tegra194-rqx-58g-user-custom.dtb # Then, shutdown the system sudo shutdown -h now
/opt/nvidia/jetson-io/config-by-hardware.py -l
を実行すると、利用可能なオーバーレイ オプションを確認することができます。
$ sudo /opt/nvidia/jetson-io/config-by-hardware.py -l
[sudo] password for ros:
Header 1 [default]: Jetson 40pin Header
No hardware configurations found!
Header 2: Jetson AGX Xavier CSI Connector
Available hardware modules:
1. TIERIV IMX490 GMSL2 Camera Device Tree Overlay
2. TIERIV ISX021 GMSL2 Camera Device Tree Overlay
3. TIERIV ISX021 IMX490 GMSL2 Camera Device Tree Overlay
たとえば、すべての GMSL ポートを C2 カメラに割り当てるには、overlay コマンドは次のようにして下さい。
sudo /opt/nvidia/jetson-io/config-by-hardware.py -n 2="TIERIV IMX490 GMSL2 Camera Device Tree Overlay"
C1 と C2 の両方に GMSL ポートを割り当てるには、overlay コマンドを次のようにして下さい。
sudo /opt/nvidia/jetson-io/config-by-hardware.py -n 2="TIERIV ISX021 IMX490 GMSL2 Camera Device Tree Overlay"
この場合、ポート 1、2、5、および 6 は C1 に割り当てられ、ポート 3、4、7、および 8 は C2 に割り当てられます。
デバイスオーバーレイの詳細については、デバイスドライバの GitHub リポジトリを参照してください。
1.1.2.4. ROSCube-X がカメラを認識しているかの確認#
ターミナルウィンドウを開き、次のコマンドを入力します。 /dev/videoX
が返された場合、カメラはビデオ デバイスとして正しく認識されています。
ls /dev/video*
/dev/video0
/dev/video1
.
.
.
/dev/video7 # When 8 cameras are connected
1.1.2.5. GStreamer を使用したカメラ出力の視覚化#
ターミナルウィンドウを開き、次のコマンドを入力します。 Gstreamerが起動し、新しいウィンドウにカメラ画像ストリームが表示されます(図4、図5)
1.1.2.5.1. ケース 1: 1 台の C1 カメラが接続されている場合#
# If cameras are running in slave mode, execute this i2cset command first
i2cset -f -y 2 0x66 0x04 0xff
# Start streaming
gst-launch-1.0 v4l2src io-mode=0 device=/dev/video0 do-timestamp=true ! 'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! videoscale ! xvimagesink sync=false
1.1.2.5.2. ケース 2: 8 台の C1 カメラが接続されている場合#
# If cameras are running in slave mode, execute this i2cset command first
i2cset -f -y 2 0x66 0x04 0xff
# Start streaming
gst-launch-1.0 v4l2src io-mode=0 device=/dev/video0 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! \
xvimagesink sync=false v4l2src io-mode=0 device=/dev/video1 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! xvimagesink sync=false \
v4l2src io-mode=0 device=/dev/video2 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! xvimagesink sync=false \
v4l2src io-mode=0 device=/dev/video3 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! xvimagesink sync=false \
v4l2src io-mode=0 device=/dev/video4 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! xvimagesink sync=false \
v4l2src io-mode=0 device=/dev/video5 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! xvimagesink sync=false \
v4l2src io-mode=0 device=/dev/video6 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! xvimagesink sync=false \
v4l2src io-mode=0 device=/dev/video7 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! xvimagesink sync=false \
参考
複数カメラを接続し、上記のコマンドでカメラを起動してカメラの起動が不安定な場合、こちらのページを参照ください。
1.1.2.5.3. ケース 3: C2 カメラ 1 台が接続されている場合#
gst-launch-1.0 v4l2src io-mode=0 device=/dev/video0 do-timestamp=true ! 'video/x-raw, width=2880, height=1860, framerate=30/1, format=UYVY' ! videoscale ! xvimagesink sync=false
C2カメラに関する制限事項
現在、2 台の C2 カメラを 1 つのデシリアライザ ボードに接続することはできません。
例:
ポート1および2 ... NG
ポート 3 と 4 ... NG
ポート1とポート3 ... OK
ポート 1 と 5 ... OK
カメラの起動順序の制約 (v1.1.1 以前のドライババージョンの場合)
v1.1.1 より前のバージョンのドライバを使用している場合は、起動のための特定の手順に従ってください。ドライババージョン v1.2.1 以降の場合、順序や制約の要件はありません。
複数のカメラを実行するには、カメラを一度に起動する必要があります。たとえば、2 台のカメラを実行するには、start-streaming コマンドをワンライナーにする必要があります。
# This one-liner command works
gst-launch-1.0 v4l2src io-mode=0 device=/dev/video0 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! \
xvimagesink sync=false v4l2src io-mode=0 device=/dev/video1 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! xvimagesink sync=false \
これらの個別のコマンドは機能しません
# These separated commands may not work
# On a terminal
gst-launch-1.0 v4l2src io-mode=0 device=/dev/video0 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! \
xvimagesink sync=false
# On another terminal
gst-launch-1.0 v4l2src io-mode=0 device=/dev/video1 do-timestamp=true ! \
'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! \
xvimagesink sync=false
1.1.3. 映像データをrosbag(ROS形式のログデータ)として記録する#
1.1.3.1. ROS melodic と gscam (GStreamer 用の ROS カメラドライバー) のインストール#
コマンドラインで次の入力を行い、ROS melodic と gscam をインストールして下さい。
注意
インストールコマンドは変更される可能性があります。次のコマンドが機能しない場合は、ROS 公式ドキュメント を参照してください。
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
sudo apt update
sudo apt install ros-melodic-desktop
echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc
sudo apt install -y ros-melodic-gscam
1.1.3.2. gscam の実行と画像トピックの可視化#
以下の手順で gscam を実行して下さい。
新しいターミナルを開き、次のコマンドを実行してroscoreを起動します
roscore
別のターミナルを開き、次のコマンドを実行します
export GSCAM_CONFIG="v4l2src device=/dev/video0 ! video/x-raw,framerate=30/1 ! videoconvert" rosrun gscam gscam
トピック(ROS形式のメッセージデータ)camera/image_rawが公開されたので、rqt_image_viewでトピックを可視化します。 rqt_image_view を起動するには、別のターミナルを開いて次のコマンドを実行します。
rosrun rqt_image_view rqt_image_view
このコマンドは、画像トピックを視覚化するためのウィンドウを開きます。ウィンドウ左上のプルダウンメニューをクリックして、camera/image_rawを選択します(図6)。
複数のカメラで gscam を実行するには、次の XML メッセージを含むテキスト ファイルを作成し、~/2cameras.launch
として保存します。この .launch ファイルは 2 台のカメラでのストリーミング用です。
<launch>
<arg name="frame_rate" default="30"/>
<node name="gscam_driver_v4l_port_1" pkg="gscam" type="gscam" output="screen" ns="port_1">
<param name="camera_name" value="port_1"/>
<param name="frame_id" value="port_1"/>
<param name="camera_info_url" value="package://gscam/examples/uncalibrated_parameters.ini"/>
<param name="gscam_config" value="v4l2src device=/dev/video0 ! video/x-raw,format=UYVY,width=1920,height=1280,framerate=30/1 ! videoconvert"/>
<param name="sync_sink" value="true"/>
</node>
<node name="gscam_driver_v4l_port_2" pkg="gscam" type="gscam" output="screen" ns="port_2">
<param name="camera_name" value="port_2"/>
<param name="frame_id" value="port_2"/>
<param name="camera_info_url" value="package://gscam/examples/uncalibrated_parameters.ini"/>
<param name="gscam_config" value="v4l2src device=/dev/video1 ! video/x-raw,format=UYVY,width=1920,height=1280,framerate=30/1 ! videoconvert"/>
<param name="sync_sink" value="true"/>
</node>
</launch>
注意
上記はC1の設定です。 C2の場合は、必要に応じて「width」、「height」、「framerate」を変更してください。
/home/ros/2cameras.launch
を作成したとして、次のコマンドを実行して複数のカメラで gscam を実行します。
roslaunch /home/ros/2cameras.launch
注釈
さらにカメラを追加するには、適切なnode name、namespace(ns)、camera_name、frame_id、および gscam_config を使用してノードを追加します。
1.1.3.3. Rosbagを記録する#
gscam の実行中に、次の方法で rosbag (ROS 形式のログ ファイル) を記録できます。
rosbag record -a
rosbag info で rosbag の情報を確認することができます。
rosbag info <recorded rosbag file name>
# example output
path: 2022-03-29-17-42-07.bag
version: 2.0
duration: 3.1s
start: Mar 29 2022 17:42:07.97 (1648543327.97)
end: Mar 29 2022 17:42:11.07 (1648543331.07)
size: 365.7 MB
messages: 113
compression: none [53/53 chunks]
types: rosgraph_msgs/Log [acffd30cd6b6de30f120938c17c593fb]
sensor_msgs/CameraInfo [c9a58c1b0b154e0e6da7578cb991d214]
sensor_msgs/Image [060021388200f6f0f447d0fcd9c64743]
topics: /port_1/camera/camera_info 26 msgs : sensor_msgs/CameraInfo
/port_1/camera/image_raw 26 msgs : sensor_msgs/Image
/port_2/camera/camera_info 26 msgs : sensor_msgs/CameraInfo
/port_2/camera/image_raw 26 msgs : sensor_msgs/Image
/rosout 8 msgs : rosgraph_msgs/Log (3 connections)
/rosout_agg 1 msg : rosgraph_msgs/Log
1.1.4. 設定変更#
ドライバの設定を変更するには、設定ファイル /etc/modprobe.d/tier4-*.conf
を編集します。 (次のセクションを参照してください)。設定ファイルにはデフォルトで次の行が含まれています。 (C1の場合です)
options tier4_isx021 trigger_mode=0 enable_auto_exposure=1 enable_distortion_correction=1
設定を適用するには、編集後に ROSCube-X を再起動します。
1.1.4.1. 駆動モードの切り替え#
注意
カメラをスレーブモードで動作させるには、ROSCube-Xからフレーム同期信号を入力する必要があります。カメラをスレーブ モードで駆動するには、Shutter triggering over GMSL2 をチェックしてください。
1.1.4.1.1. C1の場合#
設定ファイルを編集することで、カメラの駆動モードをマスター モードからスレーブ モード (またはその逆) に切り替えることができます。
マスターモード: 30fpsのフリーランモード(デフォルト)
スレーブモード: シャッタートリガーモード。シャッタータイミング、フレームレートは FSYNC 信号周波数によって調整可能 (ROSCube-X で設定可能)
モードを切り替えるには、/etc/modprobe.d/tier4-isx021.conf
のtrigger_mode
を編集します。 (以下参照)
駆動モード |
フレームレート |
trigger_mode= |
マスター |
30fps |
0 |
スレーブ |
FSYNC入力周波数に依存 |
1 |
1.1.4.1.2. C2の場合#
C2の場合、/etc/modprobe.d/tier4-imx490.confを編集することで以下のモードを選択することができます。次の表に、使用可能な設定を示します。
駆動モード |
フレームレート |
trigger_mode= |
マスター |
10fps |
0 |
スレーブ |
10fps |
1 |
マスター |
20fps |
2 |
スレーブ |
20fps |
3 |
マスター |
30fps |
4 |
スレーブ |
30fps |
5 |
1.1.4.2. レンズ歪み補正 (LDC) の有効化/無効化#
注釈
この設定は C1 と C2 に共通です。
LDC を有効にするには、フラグ enable_distortion_correction=1
(デフォルト) を設定します。 LDC を無効にするには、フラグ enable_distortion_correction=0
を設定します。
1.1.4.3. オートエクスポージャーの有効化/無効化#
注釈
この設定は C1 と C2 に共通です。
LDC を有効にするには、フラグ enable_distortion_correction=1
(デフォルト) を設定します。 LDC を無効にするには、フラグ enable_distortion_correction=0
を設定します。
1.1.4.4. 露光時間の固定#
1.1.4.4.1. C1の場合#
C1には3種類の露光時間があり、変数 shutter_time_min
, shutter_time_mid
, shutter_time_max
を使用することで各々を設定することが可能です。実際の露光時間は、周囲の明るさに応じてこれら3つの3変数値及びそれらの線形補間値の間を遷移します。各変数値の単位はマイクロ秒です。異なる環境光条件下であっても露光時間が変化しないように固定するには、これらの変数に対してすべて同じ値を設定してください。例えば、 /etc/modprobe.d/tier4-isx021.conf
に対して以下の設定を記述することで露光時間を11 msに固定することができます。
shutter_time_min=11000 shutter_time_mid=11000 shutter_time_max=11000
1.1.4.4.2. C2の場合#
C1と同様に、C2では shutter_time_min
及び shutter_time_max
の2種類の露光時間を設定することが可能です。各変数値の単位はマイクロ秒です。例えば、 /etc/modprobe.d/tier4-imx490.conf
に対して以下の設定を記述することで、露光時間を11 msに固定することができます。
shutter_time_min=11000 shutter_time_max=11000
1.1.5. GMSL2 経由のシャッタートリガー#
スレーブ モードでのカメラ操作には、GMSL2 を介したトリガー信号入力 (FSYNC 入力) が必要です。 FSYNC パラメータと GPIO 設定の構成方法については、ADLINK のドキュメント を参照してください。
1.1.5.1. スレーブモードでカメラを駆動するための準備#
ターミナルでi2cget -f -y 2 0x66 0x01
を実行して ROSCube-X の HW バージョンを確認し、以下の手順に従ってください。
ストリーミングを開始する前に i2cset -f -y 2 0x66 0x04 0xff
を実行してください。システムでは、起動後にこの準備が 1 回だけ必要になります。
準備は必要ありません。
1.1.5.2. C1のFSYNC周波数#
30fpsより低い任意の周波数を入力可能です
1.1.5.3. C2のFSYNC周波数#
C2の場合、入力可能なFYNCの周波数は駆動モードに依存します。以下の表を参照して下さい。
30fps モード (
trigger_mode=5
): 15 < f <= 30 fps20fps モード (
trigger_mode=3
): 10 < f <= 20 fps10fps モード (
trigger_mode=1
): 5 < f <= 10 fps
1.1.5.4. フレームレートの確認#
ビデオ上で フレームレート設定を確認するには、次のコマンドを実行してください。
カメラがポート 1 にのみ接続されてる場合
gst-launch-1.0 v4l2src io-mode=0 device=/dev/video0 do-timestamp=true ! 'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! fpsdisplaysink video-sink=xvimagesink sync=false
カメラがポート 1 と 2 に接続されている場合
gst-launch-1.0 v4l2src io-mode=0 device=/dev/video0 do-timestamp=true ! 'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! xvimagesink sync=false v4l2src io-mode=0 device=/dev/video1 do-timestamp=true ! 'video/x-raw, width=1920, height=1280, framerate=30/1, format=UYVY' ! fpsdisplaysink video-sink=xvimagesink sync=false