Jetson TX1でZEDを使う


Environment

  • NVIDIA Jetson TX1

https://developer.nvidia.com/embedded-computing
tx1.png

  • Stereolabs ZED

https://www.stereolabs.com/zed/specs/

PreInstall

CPU Fanを有効にする

# ref: http://elinux.org/Jetson/TX1_Controlling_Performance
sudo sh -c 'echo 255 > /sys/kernel/debug/tegra_fan/target_pwm'

当初CPUファンが回っていなかったからか、途中で固まってしまいました。。

Installation

JetPackを使ってOpenCV/CUDAインストール

ZEDはCUDA対応しているのでまずはCUDAを入れる。

  1. TX1 32-bitを選択(TX1はCPUは64bitだが、OSはデフォルトでは32bit)
  2. 最低限のものだけ選択(必要のないものを"no action"へ変更する)
  3. あとはダイアログに従う。

ZEDをTX1に挿す。

  • ZED SDKをインストールする最後にキャリブレーションが行われる。

ZED SDKをインストール

ROSインストール

sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu trusty main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net --recv-key 0xB01FA116
sudo apt-get update
sudo apt-get install -y -qq git python-rosdep python-wstool python-catkin-tools ros-indigo-rosbash ros-indigo-roslib
sudo rosdep init
rosdep update
mkdir -p ~/ros/indigo/src
cd ~/ros/indigo/src
wstool init
wstool set zed-ros-wrapper --git https://github.com/stereolabs/zed-ros-wrapper
wstool up
rosdep install --from-paths . --ignore-src -r -n -y
cd ~/ros/indigo
catkin init
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
catkin build
echo 'source $HOME/ros/indigo/devel/setup.bash' >> ~/.bashrc
exec -l $SHELL
  • キャリブレーションファイルの手動ダウンロード

カメラ起動時にキャリブレーションファイルを取ってくるが、Firewallの設定などで失敗する場合がある。その場合は公式サイトからキャリブレーションファイルをダウンロードしてきて、 /usr/local/zed/settingsに置く。

Run

画像・点群を見てみる

  • Viewerのインストール
sudo apt-get install -y -qq ros-indigo-rqt-image-view ros-indigo-rviz

# ref: http://answers.ros.org/question/223995/rviz-bus-error-on-nvidia-jetson-tx1-board/
echo 'unset GTK_IM_MODULE' >> ~/.bashrc
exec -l $SHELL
  • カメラの起動
roslaunch zed_wrapper zed.launch
  • 画像表示
rqt_image_view
# /camera/rgb/image_rect_color などを選択
  • 点群表示
rviz
# Fixed Frameをzed_initial_frameに
# Add -> PointCloud2
# Topic: /camera/point_cloud/cloud, Color Transformer: RGB8

SLAMしてみる

  • インストール
sudo apt-get install -y -qq ros-indigo-rtabmap-ros
  • 以下のようなlaunchファイルを作る
<!-- zed_rtabmap.launch -->
<launch>
  <arg name="rviz" default="false" />
  <arg name="rtabmapviz" default="true" />
  <node name="camera_to_zed_frame"
    pkg="tf" type="static_transform_publisher"
    args="0 0 0 -1.5707963267948966 0 -1.5707963267948966 camera_link zed_initial_frame 100" />
  <include file="$(find rtabmap_ros)/launch/rgbd_mapping.launch">
    <arg name="rtabmap_args" value="--delete_db_on_start" />
    <arg name="depth_registered_topic" value="/camera/depth/image_rect_color" />
    <arg name="rviz" value="$(arg rviz)" />
    <arg name="rtabmapviz" value="$(arg rtabmapviz)" />
  </include>
</launch>
  • 起動する
roslaunch zed_wrapper zed.launch
roslaunch zed_rtabmap.launch

下記画像右側に世界座標系から見たカメラの軌跡と重ねあわせられた点群が表示されているのがわかる。

画面が赤くなったら自己位置を喪失したということのようなので、一時停止ボタンを押し、Reset Odometryを押す。
recover.png

  • すごい