Darknet_ros_FP16レポート(1.3倍高速)
皆さんこんにちは。この記事ではdarknet_ros + ROS2 Foxy + cuDNNの軽い解説とそのベンチマーク結果について報告したいと思います。
この記事をご覧になっているということはdarknet_ros(あるいはdarknet)を既に知っているという方が多いと思います。
そう、ロボットでAIを活用した物体検出をしたいと思ったら真っ先に思いつくプログラムですね!?Joseph Redmon氏が開発したオープンソースの高速物体検出プログラムで、TensorFlowやCaffeなどに依存せずに最初からCで書かれているのが特徴的です。
この論文とプログラムの衝撃は非常に大きく、そのGitHubページには20.9kのスターと17.4kのフォークがついています。
それから現在までその派生となるYOLO v4 (Alexey Bochkovskiy氏)やYOLO R・Scaled-YOLO v4 (Kin-Yiu, Wong氏)、YOLO v5 (Glenn Jocher氏)が開発され、matlabやOpenCVなどの様々な言語やライブラリに移植されています。
その高速な物体検出アルゴリズムをROSで動かそう!ということで開発されているのがdarknet_rosで、Jetsonなどの組み込みコンピュータとの相性の良さからROS+物体検出の定番として記事が多く書かれています。
ここまで簡単ですがdarknetとdarknet_rosについて解説しました。
darknet ROSにYOLO v4がない!
darknet (YOLO v4) は前述の通りAlexey Bochkovskiy氏が中心になって開発を進められているプロジェクトでこちらも本家に負けず劣らず16.5kのスターがつけられています。こちらはC++化が進み、OpenCV4やcuDNNにも対応するようになって非常に使い勝手のよいプログラムになりました。
しかし、2021年6月時点でもdarknet_rosのフォーク元は本家の方になっており、YOLO v4が使えない状況が続いています。(開発者はいずれ実装したいらしいが・・)
これは、少し仕方のない部分もあります。
darknet自体は2015年に最初の論文が公開されたもので、かなりライブラリも古いものが使われていた関係上、現在のデフォルト環境では動かない場合があります。(そして、Joseph Redmon氏のDarknetは2018年を最後に開発が終了してしまいました…)
バージョンによる不具合対応例:https://github.com/AlexeyAB/darknet/issues/932
darknet_rosもOpenCV4や新しいROSへの対応などが進んでおり、現在も新しいプルリクが投げられていますが、YOLO v4への対応(=サブモジュールのAlexeyAB化)にはとても大きな変更を加える必要があります。
ちなみに、ROS1のdarknet_rosでYOLO v4に対応したサイトやリポジトリはいくつかあります。
しかし、私はROS2で動くdarknet_rosがどうしても欲しくなりました…
そこで、4月下旬にdarknet_rosでYOLO v4を動かしたいと思い、5月頃に実装しました。
これに関してはいろいろな記事でちょこちょこと公開したり、GitHubでリポジトリ作ってPR出したり、Twitterで結果を公表したりしていました。
動作報告もありがたいことにいくつか頂いています。
そこから1ヶ月半、さらなる高速化を実現し、darknet_rosの中でも本家実装の速さに近いリポジトリになったことを結果付きで報告したいと思います。
cuDNNとFP16とは
高速化のためにはAlexeyAB/darknetでサポートされているcuDNNとFP16 (CUDNN_HALF) のサポートをdarknet_ros側でも行う必要があります。
ここで、cuDNNとFP16について少し解説します。
NVIDIAのCUDAライブラリ群にはディープラーニングに特化したライブラリ「cuDNN」があります。これは、CUDAに標準で入っているdnnモジュールをさらに高速化できる外付けライブラリです。
cuDNNはCUDAではサポートしきれない深層学習モジュールの最適化を行うライブラリで、Makefileに追加することで有効化できるため、cuDNNがもとのCUDAのライブラリを一部上書きしているといえます。
FP16はcuDNNの中に入っている機能の一つで、これが非常に強いです。通常のCUDAの演算では単精度浮動小数点を扱っています。これは、普段使うCPUのfloatとほぼ同じ要素で、広い数字の範囲を扱うことができます。しかし、入力される色はもともと256段階しかないので、そんなに広く値を取る意味があまりありません。そこで、FP16を使って表現と精度を半分にすることでより同じメモリ使用量で倍近くの演算を可能にすることができます。これによって速度が1.3〜1.5倍速くなるそうです。
https://github.com/AlexeyAB/darknet#geforce-rtx-2080-ti より
ただし、FP16はハードウェア側のサポートが必要で、Voltaの一部GPUやTuring以降のGPUが必要になります。これらのGPUには共通してTensor Coreが含まれるため、これを基準にして選定すると外れなさそうです。
使えるGPU(cm_70を超えるもの)
- GeForce RTX系列(Laptop含む)
- Quadro RTX系列
- Jetson Xavier (NX含む?)
- TITAN V、NVIDIA TITAN RTX
- NVIDIA V100、T4、Aシリーズ
cuDNN導入の簡単な解説
ここからはcuDNNの導入のためのCMakeLists.txtの解説を少しします。cuDNNの有効化にはかなり手こずったので、抜粋して示すことで必要な人に修正点がわかりやすく伝えられればいいなと思います。
↓ cuDNNがサポートされたdarknet_rosのGitHubリポジトリはこちらから
CMakeLists.txtを記載する際は、どんな環境でも対応できるようにFindコマンドとifコマンドで条件分岐を行う必要があります。
cuDNNを探すヒントが最初から与えられているわけではないので、set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../darknet/cmake/Modules/" ${CMAKE_MODULE_PATH})
でAlexeyAB/darknetのFindCUDNN.cmakeを参照する必要があります。オリジナルなパッケージを作る場合は自分で用意する必要があります。
そして、見つかったら、その条件に合わせて関連付けを行います。
#--- 省略 ---
## ベンチマーク用
set(CUDA_ENABLE ON)
set(CUDNN_ENABLE ON)
set(FP16_ENABLE ON)
#--- 省略 ---
## FindCUDNN.cmakeを探す
set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../darknet/cmake/Modules/" ${CMAKE_MODULE_PATH})
if(CUDNN_ENABLE)
find_package(CUDNN) ## cuDNNの探索
message(STATUS "cuDNN Version: ${CUDNN_VERSION_STRINGS}")
message(STATUS "cuDNN Libararies: ${CUDNN_LIBRARIES}")
endif()
## cuDNNが見つかった場合
if(CUDNN_FOUND)
set(ADDITIONAL_CXX_FLAGS "${ADDITIONAL_CXX_FLAGS} -DCUDNN") # <- cuDNN有効化
endif()
#--- 省略 ---
## cuDNNを使う場合
if(CUDNN_FOUND)
## cuDNNのFP16も使う場合
if(ENABLE_CUDNN_HALF)
target_link_libraries(${PROJECT_NAME}_lib
cuda
cudart
cublas
curand
CuDNN::CuDNN ## <-- cuDNN有効化
)
target_compile_definitions(${PROJECT_NAME}_lib PRIVATE
-DCUDNN ## <-- cuDNN有効化
-DCUDNN_HALF ## <-- FP16有効化
)
## cuDNNのFP16を使わない場合
else()
target_link_libraries(${PROJECT_NAME}_lib
cuda
cudart
cublas
curand
CuDNN::CuDNN ## <-- cuDNN有効化
)
target_compile_definitions(${PROJECT_NAME}_lib PRIVATE
-DCUDNN ## <-- cuDNN有効化
)
endif()
## cuDNNを使わない場合 --省略--
endif()
アーキテクチャによるCUDNN_HALF (FP16)の判断
CUDNN_HALFの有効化手法については、GPUを調べて手動で設定するのが最も正確ですが、最初は気づくことなくコンパイルすると思うので、自動で対象外のモジュールを弾くシェルをCMakeLists.txt内に書きました。lspciコマンドを使って対象アーキテクチャのGPUを表示させて、表示されなかったら弾くというシステムにしています。そのため、Jetson AGX XavierなどのGPUはデフォルトで弾かれてしまいます。その際は17行目の# set(CMAKE_CUDA_ARCHITECTURES 72)
をコメントアウトします。
execute_process (
COMMAND bash -c "lspci | grep NVIDIA | grep -e TU106 -e TU104 -e TU102 -e GA106 -e GA104 -e GA102"
OUTPUT_VARIABLE outVar
)
message ( STATUS " GPU (FP16): " ${outVar} )
if(outVar AND FP16_ENABLE)
set(CMAKE_CUDA_ARCHITECTURES 75)
endif()
if ( 70 IN_LIST CMAKE_CUDA_ARCHITECTURES OR
72 IN_LIST CMAKE_CUDA_ARCHITECTURES OR
75 IN_LIST CMAKE_CUDA_ARCHITECTURES OR
80 IN_LIST CMAKE_CUDA_ARCHITECTURES OR
86 IN_LIST CMAKE_CUDA_ARCHITECTURES)
set(ENABLE_CUDNN_HALF "TRUE" CACHE BOOL "Enable CUDNN Half precision" FORCE)
message(STATUS "Your setup supports half precision (CUDA_ARCHITECTURES >= 70)")
else()
set(ENABLE_CUDNN_HALF "FALSE" CACHE BOOL "Enable CUDNN Half precision" FORCE)
message(STATUS "Your setup does not support half precision (it requires CUDA_ARCHITECTURES >= 70)")
endif()
速度検証用
CUDA、CUDNN、CUDNN_HALF (FP16)の有効化・無効化が可能です。現時点では、CUDA=OFFだとエラーになります。また、CUDA=OFFのときにCUDNNは有効化されず、CUDNNが有効化されていないときはCUDNN_HALFは有効になりません。
set(CUDA_ENABLE ON)
set(CUDNN_ENABLE ON)
set(FP16_ENABLE ON)
インストール
依存環境を次に示します。
必要
- ROS2 Dashing以降
- OpenCV3.2以降
- CUDA 10.0以降(Ampere以降はCUDA 11.0以降)
- NVIDIA CUDA環境が実行可能な4GB VRAM搭載のGPU
必要に応じて
-
cuDNN 7以降 (CUDAのバージョンに合わせてください)
-
NVIDIA CUDA環境が実行可能な6GB VRAM搭載のGPU
-
FP16演算が可能なGPU
上記のインストールが終了している前提で次のコマンドを入力します。
source /opt/ros/foxy/setup.bash
mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
git clone --recursive https://github.com/Ar-Ray-code/darknet_ros_fp16.git
darknet_ros_yolov4/darknet_ros/rm_darknet_CMakeLists.sh
cd ~/ros2_ws
colcon build --symlink-install
ウェブカメラが接続されている状態で次のコマンドを入力して実行します。
source /opt/ros/foxy/setup.bash
source ~/ros2_ws/install/local_setup.bash
ros2 launch darknet_ros demo-v4-tiny.launch.py
ロード中にcudnn_half=1となっていればOKです。
実行して画像が表示されれば実行成功です。やったね🎉🎉🎉
終了したい時はCtrl+Cで停止しましょう。
ベンチマーク(本題)
さて、本題は何だったでしょうか…??あ、そうでした。「FP16でどれくらい速くなったか」でしたね
これはグラフを見てもらったほうが早いでしょう。
次の環境でテストしました。また、次の前提でベンチマークを取っています。
-
RTX 2080 TiとJetson AGX Xavierの速度比を検証するものではない。あくまで同じモデル・環境での速度比を確認するものです。
-
モデルはダウンロードしたものをそのまま使い、TensorRTなどの処理を行っていません。
-
速度については、非常に値のブレが多く計算によってボトルネックが発生するため、平均FPSを算出しない代わりに最大FPSと最小FPSを取りました。目視での感想ですが、最頻値は(最大FPS-最低FPS)x0.7+最低FPSに近いです。
-
-gencode arch=compute_75,code=[sm_75,compute_75]
などの最適化設定は手動で行いました。 -
速度について、開始直後の最大FPS・最低FPSは取りません。1分間放置後に反映されている速度を結果として記載しました。
-
このベンチマーク専用のブランチを使いました。
使用した重みファイルは次の4つです
- YOLOv4x-mish.weights (640)
- YOLO v4.weights (608)
- YOLOv4-scp.weights (512)
- YOLOv4-tiny (416)
環境1:RTX 2080 Ti
Topics | Spec |
---|---|
CPU | Ryzen7 2700X (@3.7GHz x 16) |
RAM | 16GB DDR4 |
GPU | NVIDIA GeForce RTX 2080 Ti (GDDR6 11GB) |
Driver | 465.19.01 |
Topics | Version |
---|---|
Ubuntu | 20.04 LTS |
ROS | Foxy |
CUDA | 11.3 |
cuDNN | 8.2.1 |
OpenCV | 4.2 |
YOLOv4-tinyで167FPS🔥🔥🔥🔥🔥🔥🔥🔥
環境2:Jetson AGX Xavier (MAXN)
Topics | Spec |
---|---|
CPU | 8-core ARM v8.2 64-bit CPU, 8MB L2 + 4MB L3 |
RAM | 32 GB 256-Bit LPDDR4x |137 GB/s |
GPU | 512-core Volta GPU with Tensor Cores |
Driver | JetPack 4.4.1 |
Topics | Version |
---|---|
Ubuntu | 18.04 LTS |
ROS | Dashing |
CUDA | 10.2 |
cuDNN | 8.0 |
OpenCV | 4.1 |
※Jetson AGX Xavierでは、YOLOv4.weightsとYOLOv4x-mishの実行ができませんでした。
YOLOv4-tinyで98FPS🔥🔥🔥🔥🔥🔥🔥🔥
考察・結論
RTX 2080 TiとJetson AGX Xavierに関して共通して言えることは次の3つです。
- FP16で特にFPSが伸びる。
- 重いファイルほど瞬間FPSの伸びが大きい。
- 全体的にはcuDNN (FP16)の速度はcuDNN非使用と比べて1.3倍程度速くなる。
ただし、Jetson AGX Xavierについては、cuDNNを使用する際はFP16を有効にしないとあまり意味が無いということが分かりました。
最近は物体検出を用いた自動化アプリケーションが多く開発されるようになり、AI製品がより身近になりつつあります。そして、様々なライブラリの急速な進化やROS2など新記法の普及に伴い、様々なモジュールの移植が進みつつある現在、「移植力」がかなり必要な能力になるつつあるのではないのかと勝手ながら推測しています。
ROSでYOLO v4モデルを使いたい人の役に立てるとうれしいです。
この資料をもって大胆な改良をひとまず終了したいと思いますが、質問やわからないところがあれば、遠慮なくGitHubやTwitterで質問していただければ可能な限り答えたいと思います。
参考資料一覧
Discussion