2021年5月5日水曜日

ultra96v2でVitis 2020.2を使用してcv::fastをxf::cv::fastに置き換えて見た話

xf::cv::fastはコーナ部分をMatで固定値255として出力してくる。ORB_SLAM2ではコーナスコアを使用して特徴点の数を間引くので、そのままだと不都合がある。

そこでcv::fastで出力している特徴点リストと、明確さ(CornerScore)をxf::cv::fastから出力するように変更する。直接変更座標を出力するようにしたほうがリソースと速度の面から有利かもしれないので、後の改善項目として検討する。

この後は間引き処理もカーネルに取り込み、全体の並列動作を調整していく。

環境

  • ubuntu:20.04
  • vitis:2020.2
  • yocto:zeus(https://github.com/akira-nishiyama/petalinux-ros2-manifests feature-v2020.2ブランチ)
  • board:ultra96v2(https://github.com/akira-nishiyama/ultra96v2_4z.git feature-v2020.2ブランチ)

変更点

デフォルトではコーナースコアが出力されないので、以下のように変更する。

diff --git a/hw/hw_kernel/vision/include/features/xf_fast.hpp b/hw/hw_kernel/vision/include/features/xf_fast.hpp
index a7aa1b1..935c0a2 100644
--- a/hw/hw_kernel/vision/include/features/xf_fast.hpp
+++ b/hw/hw_kernel/vision/include/features/xf_fast.hpp
@@ -201,7 +201,8 @@ void xFfastProc(XF_PTNAME(DEPTH) OutputValues[XF_NPIXPERCYCLE(NPC)],
         // NMS Score Computation
         if (iscorner) {
             xFCoreScore(flag_d[i], _threshold, &core);
-            pack_corners.range(ix + 7, ix) = 255;
+            //pack_corners.range(ix + 7, ix) = 255;
+            pack_corners.range(ix + 7, ix) = core;
         } else
             pack_corners.range(ix + 7, ix) = 0;
         ix += 8;
@@ -570,7 +571,8 @@ void xFnmsProc(XF_PTNAME(DEPTH) OutputValues[XF_NPIXPERCYCLE(NPC)],
         if ((src_buf[1][1] > src_buf[1][0]) && (src_buf[1][1] > src_buf[1][2]) && (src_buf[1][1] > src_buf[0][0]) &&
             (src_buf[1][1] > src_buf[0][1]) && (src_buf[1][1] > src_buf[0][2]) && (src_buf[1][1] > src_buf[2][0]) &&
             (src_buf[1][1] > src_buf[2][1]) && (src_buf[1][1] > src_buf[2][2])) {
-            pix = 255;
+            //pix = 255;
+            pix = src_buf[1][1];
         } else {
             pix = 0;
         }

sw_emu

build

OpenCVの結果と比較するテストプログラムで確認する。 hashは85f0af60868b7a0ba831647bcfd453f4b6b19c6c

git clone https://github.com/akira-nishiyama/orb_slam_2_ros.git -b feature-fpga
cd orb_slam_2_ros
mkdir build
cd build
source <vitis-installation-path>/settings64.sh
source <sdk-installation-path>/environment-setup-aarch64-xilinx-linux
export AMENT_PREFIX_PATH=$OECORE_NATIVE_SYSROOT/usr:$OECORE_TARGET_SYSROOT/usr
export PYTHONPATH=$OECORE_NATIVE_SYSROOT/usr/lib/python3.7/site-packages:$OECORE_TARGET_SYSROOT/usr/lib/python3.7/site-packages
cmake .. -DCMAKE_INSTALL_SO_NO_EXE=0 -DBUILD_TESTING=OFF -DCMAKE_NO_SYSTEM_FROM_IMPORTED=1 -GNinja -DCMAKE_INSTALL_PREFIX=/media/akira/usr -DPLATFORM_COMPONENTS_PATH=/home/akira/work/ultra96v2 -DBUILD_TEST_TARGETS=OFF -DBUILD_TARGET=sw_emu -DCMAKE_BUILD_TYPE=Debug -DENABLE_KRNL_CHECK=OFF -DBUILD_FAST_TEST=OFF -DBUILD_FAST_AND_DIST_TEST=ON -DDISABLE_RESIZE_KRNL=ON -DDISABLE_FAST_KRNL=OFF
ninja -j4

run

cd hw/hw_link/package_sw_emu/
source <vitis-installation-path>/settings64.sh
./launch_sw_emu.sh -pid-file emulation.pid -no-reboot -forward-port 2222 22

ターミナルで以下の通り実行する。

cd /mnt/sd-mmcblk0p1
export LD_LIBRARY_PATH=/mnt/sd-mmcblk0p1:/tmp:$LD_LIBRARY_PATH
export XCL_EMULATION_MODE=sw_emu
export XILINX_XRT=/usr
export XILINX_VITIS=/mnt/sd-mmcblk0p1
./xf_fast_and_dist_tb 128x128_1.png

result

============ xf_fast_and_dist test starts ============
INFO: Running OpenCL section.
Found Platform
Platform Name: Xilinx
INFO: Device found - avnet_com_av_ULTRA96V2_1_0
XCLBIN File Name: krnl_fast
INFO: Importing xclbin/krnl_fast.xclbin
Loading: 'xclbin/krnl_fast.xclbin'
ocv_result:511
hls_result:511
Test Passed
The maximum depth reached by any of the 2 hls::stream() instances in the design is 16384

0 件のコメント:

コメントを投稿