Skip to content

3.3 NVIDIA ROS nodes

kaoru mabuchi edited this page Oct 17, 2018 · 38 revisions

このドキュメントでは、プロジェクトによって使用または実装されるROSノードについて説明します。

  1. Camera node
  2. DNN node
    2.1 TrailNet
    2.2 YOLO
    2.3 INT8 inference
    2.4 Running tests
  3. Controller node
   3.1 Building controller code
    3.1.1 Create workspace
    3.1.2 Build the code
   3.2 Configuring joystick
    3.2.1 Install ROS Joystick node
    3.2.2 Test joystick node
   3.3 Running the controller
    3.3.1 Running the controller only
    3.3.2 Running DNN and controller nodes
     3.3.2.1 Create catkin workspace mappings and build nodes
  4. Image publisher node

 カメラノード(gscam)は、標準ROSイメージメッセージを使用して'/camera/image_raw'トピックにパブリッシュします。
これは、TrailNet DNNや障害回避などの他のノードに情報を提供するマスターソースです。

 caffe_rosノードは、TensorRTライブラリを使用してDNN推論をサポートします。
このノードは現在、分類(TrailNet)、YOLOベースのオブジェクト検出、回帰およびセマンティックセグメンテーションなどのCaffeモデルをサポートしています。

ノードは、ネットワークのタイプと後処理オプション(TrailNetとYOLOなど)によって、さまざまな形式のメッセージを生成します。

メッセージのヘッダーのタイムスタンプは、対応するカメラメッセージのタイムスタンプと同じです。
これにより、デバッグおよびロギングの目的でDNN出力および他のノードとの画像フレームの同期が簡単になります。

 このノードは、標準画像メッセージを使用してDNN(例えば、softmax層)の出力をパブリッシュする。

softmax層のような1D出力の場合、公開画像の寸法は1x1xCであり、Cは層のサイズである(例えば、TrailNet出力層の場合は6、ImageNetのsoftmax層の場合は1000)。

メッセージのencodingフィールドは、32FCXXXという形式です(XXXはチャネル数に等しい)。
たとえば、TrailNetの場合:32FC6、ImageNetの場合:32FC1000
32は32ビットを意味し、Fは浮動を意味します。
詳細については、ROSのマニュアルを参照してください。

dataフィールドにはDNNの出力がバイト配列形式で格納されているため、32ビットのfloat型にキャストする必要があります。
デフォルトのトピック名は /caffe_ros/network/output ですが、起動ファイルまたはコマンドラインを使用して変更できます。

ノードには2つのパラメータが必要です。

prototxt_path - Caffeモデルの.prototxtファイルへのパス
model_path - Caffeモデルバイナリファイルへのパスさらに、入出力レイヤ名(input_layer/output_layer)のような他のパラメータも正しく設定されていることを確認してください。

TrailNetのコマンドラインの例:

rosrun caffe_ros caffe_ros_node __name:=trails_dnn _prototxt_path:=/data/src/redtail/models/pretrained/TrailNet_SResNet-18.prototxt _model_path:=/data/src/redtail/models/pretrained/TrailNet_SResNet-18.caffemodel _output_layer:=out

注意:rosrunを使用する場合は、パラメータにシステムパラメータの_(__)を接頭辞として使用し、値を割り当てるときは=を使用してください。

DNN nodeが何らかのデータを生成していることを確認するには、カメラノード(gscamまたはimage_pubノード経由の実カメラ)が実行されていることを確認し、rostopic echo /trails_dnn/network/outputを実行します。

出力の例:

header: 
  seq: 201
  stamp: 
    secs: 1501106944
    nsecs: 796543294
  frame_id: ''
height: 1
width: 1
encoding: 32FC6
is_bigendian: 0
step: 24
data: [110, 74, 230, 58, 135, 125, 95, 60, 228, 14, 124, 63, 133, 26, 6, 61, 156, 75, 115, 63, 91, 87, 138, 60]

dataバイト配列をfloat配列に変換するには、次の単純なPythonスクリプトを使用します。

import struct
data = bytearray([110, 74, 230, 58, 135, 125, 95, 60, 228, 14, 124, 63, 133, 26, 6, 61, 156, 75, 115, 63, 91, 87, 138, 60])
print(struct.unpack('<%df' % (len(data) / 4), data))

 ノードがpost_proc:= YOLO引き数で起動された場合、特別なYOLO後処理が適用されます。
このような場合、ノードは、特定のフォーマットのImageメッセージを使用してDNNの出力をパブリッシュします。
出力は、Wが固定されているWxHx1(したがって符号化== 32FC1)のフォーマットを持つ2Dシングルチャネル "イメージ" 6に等しく、Hは検出されたオブジェクトの数に等しい。
たとえば、DNNが2つのオブジェクトを検出した場合、出力は6x2イメージです。
検出された各オブジェクトについて、6つの値は次のとおりです。

0  : label (class) of the detected object (e.g. person or a dog).
1  : probability of this object.
2,3: x and y coordinates of the top left corner of the object in image coordinates.
4,5: width and height of the object in image coordinates.  

0:検出されたオブジェクト(例えば、人または犬)のラベル(クラス)。
1:このオブジェクトの確率。
2,3:画像座標のオブジェクトの左上隅のx座標とy座標。
4,5:画像座標におけるオブジェクトの幅と高さ。

すべての値はラベルを含む32ビット浮動小数点数です。ラベルインデックスは、PASCAL VOC 2012データセットの20クラスに対応しています。
たとえば、DNNが人物(ラベル:14)と犬(ラベル:12)を320x180の画像で検出した場合、出力は次のようになります。

Label Prob X Y Width Height
14.0 0.5 120.0 80.0 30.0 60.0
12.0 0.4 160.0 115.0 40.0 20.0

 INT8精度の推論を実行すると、ネイティブINT8をサポートするハードウェアのパフォーマンス(速度)と電力効率が向上します。
現時点では、INT8はGP102-GP106 Pascal GPUでサポートされています。
Jetson TX1とTX2はINT8命令をサポートしていないので、この場合、caffe_rosノードはFP32モードを使用します。
TensorRTのINT8ハードウェアサポートと実装の詳細については、[ここ}(https://devblogs.nvidia.com/mixed-precision-programming-cuda-8/)とここを参照してください。

redtail 2.0は、caffe_rosノードに新しいパラメータを導入しました。
値:fp32fp16、およびint8を受け入れるdata_type。既存のパラメータuse_fp16は廃止予定ですが、引き続きサポートされています。

INT8モードを使用するには、モデルの品質を損なうことのないように、モデル較正が必要です。
モデルキャリブレーション中、ネットワークにはデータセットの代表サンプルが供給され、関連する統計情報を収集し、実行時INT8推論を実行してできるだけ正確さを失わないようにします。
サンプルのキャリブレーションバッチは、実行時にネットワークが表示するものに近いものでなければなりません。
校正は一度だけ実行する必要があり、その後、実行時に後で使用されるファイルとして保存することができます。

caffe_rosノードは、キャリブレーションを有効にする2つのパラメータをサポートするようになりました。

  • int8_calib_srcは、キャリブレーションサンプルへのパス(ディレクトリまたは単一のイメージファイル)を提供します。パラメータがディレクトリの場合、すべてのファイルが読み込まれ、校正プロセスで使用されます。この処理には、画像の数に応じて時間がかかることがあります。キャリブレーションを実行すると、このパラメータを削除して(または空の文字列に設定して)、実行ごとに再キャリブレーションを回避できます。
  • int8_calib_cacheはキャリブレーションキャッシュへのパスを指定します。
    ファイルが存在する場合は、caffe_rosランタイムによってロードされ、使用されます。
    存在しない場合は、キャリブレーションプロセスで作成されます(int8_calib_srcパラメータを設定する必要があります)。

当社のTrailNetおよびYOLOモデルはFP16対応モデルとして訓練されているため、FP32およびFP16モードではこれらのネットワークで生成される結果にほとんど違いがありません。
ただし、ネットワークもINT8モードで動作するように特別な注意を払わず、INT8で得られたネットワーク結果はFP32/FP16モードの結果と異なる場合があります。

DNNノードが正常に動作していることを確認するには、caffe_rosパッケージに含まれている基本的なエンドツーエンドテストを実行します。
catkinワークスペースディレクトリで、次のコマンドを実行します(必要に応じてパスを置き換えます)。

catkin_make caffe_ros_tests
export REDTAIL_TEST_DIR=/data/src/redtail/ros/packages/caffe_ros/tests/data
export REDTAIL_MODEL_DIR=/data/src/redtail/models/pretrained
rostest caffe_ros tests_basic.launch test_data_dir:=$REDTAIL_TEST_DIR \
    trail_prototxt_path:=$REDTAIL_MODEL_DIR/TrailNet_SResNet-18.prototxt trail_model_path:=$REDTAIL_MODEL_DIR/TrailNet_SResNet-18.caffemodel \
    object_prototxt_path:=$REDTAIL_MODEL_DIR/yolo-relu.prototxt object_model_path:=$REDTAIL_MODEL_DIR/yolo-relu.caffemodel

注:TX2のようなデバイスでテストを実行するのに約2分かかることがあります。

 コントローラコードをビルドして実行するには、いくつかの追加の依存関係をコンテナにインストールする必要があります。

 次のコマンドはcatkinワークスペースを作成し、コントローラーを構築します。
このスクリプトは、プロジェクトのソースが /redtailにあることを前提としています。

これらのコマンドは、新しいコンテナを作成した後で1回だけ実行する必要があります。

CATKIN_WS=${HOME}/ws
mkdir -p ${CATKIN_WS}/src
cd ${CATKIN_WS}/src
catkin_init_workspace
git clone https://github.com/ros/angles.git
ln -s /redtail/ros/packages/px4_controller ${CATKIN_WS}/src/
cd ${CATKIN_WS}
catkin_make

コードを作成した後、次のsourceコマンドを実行して、ワークスペースのROS環境変数をロードします。

source ${CATKIN_WS}/devel/setup.bash

ログインごとにこれを避けるには、.bashrcファイルを更新します。

echo "export CATKIN_WS=\${HOME}/ws" >> ${HOME}/.bashrc
echo "source \${CATKIN_WS}/devel/setup.bash" >> ${HOME}/.bashrc

catkin_makeを変更した後にコントローラを構築することを忘れないでください。

 NVIDIA ShieldやMicrosoft XBoxコントローラなどの外部コントローラを使用して無人機を手動で制御したり、自律飛行を有効/無効にすることができます。

Dockerコンテナを起動する前に、コントローラがコンピュータに接続されていることを確認してください。

apt-get install ros-indigo-joy
roscore &
rosrun joy joy_node _dev:=/dev/input/js0

ジョイスティックのスティックやボタンを移動します。
いくつかの出力が表示されるはずです。
そうでない場合は、別のデバイスを使用してみてください。 (利用可能なジョイスティックデバイスのリストは、ls/dev/input/js *を実行することによって取得できます)

 最初のテストであるコントローラーだけを実行するには、GazeboシミュレーターMAVROSを起動してからコントローラーを起動します。

  1. Launch Gazebo:
cd /data/src/px4/Firmware
make posix_sitl_default gazebo
  1. In another terminal connected to the same running Docker container, run MAVROS:
      同じDockerコンテナに接続された別の端末で、MAVROSを実行します。
roslaunch mavros px4.launch fcu_url:="udp://:14540@127.0.0.1:14557" gcs_url:="udp://@172.17.0.1"

run_px4_docker.shスクリプトを使用して、端末を実行中のコンテナに接続することができます。
必要に応じて、ホスト上でQGroundControlを実行することもできます。

  1. In yet another terminal window, launch the joystick and controller nodes:
      さらに別のターミナルウィンドウで、ジョイスティックとコントローラノードを起動します。
cd ${CATKIN_WS}
rosrun joy joy_node _dev:=/dev/input/js0 _autorepeat_rate:=30 &
rosrun px4_controller px4_controller_node _altitude_gain:=2

ガゼボウィンドウを開き、ドローンが離陸し、ホバリングするのを見てください。
コントローラー(ジョイスティック)を使って無人機をナビゲートしてみてください。
GazeboとQGCを並べて開くと、次のように表示されます。

GAZEBO & QGC

 フェイクビデオ入力(静止画像やビデオなど)を使用してDNNとコントローラで完全なシミュレーションを実行するには、前のセクションの3つの手順をすべて実行し、DNNおよびイメージ発行元ノードを実行します。

1. Create catkin workspace mappings and build nodes:

  catkinワークスペースのマッピングを作成し、ノードを構築する:

ln -s /redtail/ros/packages/caffe_ros ${CATKIN_WS}/src/
ln -s /redtail/ros/packages/image_pub ${CATKIN_WS}/src/
cd ${CATKIN_WS}
catkin_make
source devel/setup.bash

これは一度だけ行う必要があります。

 image_pubノードは、ビデオまたはイメージファイルを読み取り、フレームをROSトピックとしてイメージメッセージとしてパブリッシュする単純なROSノードです。
imageまたはvideoファイルへのパスを指定する1つの必須パラメータimg_pathがあります。
このノードは、カスタムフレームレートの設定と、イメージの無期限の繰り返しをサポートします。
デフォルトのトピックは /camera/image_raw で、camera_topic パラメータを使用して変更できます。

ファイルのネイティブフレームレートを使用してビデオファイルからフレームをパブリッシュする例:

rosrun image_pub image_pub_node _img_path:=/data/videos/trail_test.mp4

同じ画像を繰り返し30フレーム/秒で公開する例:

rosrun image_pub image_pub_node _img_path:=/data/images/trail_right.png _pub_rate:=30 _repeat:=true

Clone this wiki locally