2021年5月1日土曜日

orb_slam2のcv::fastをxf::cv::fastで置き換えてみた話

orb_slam2のcv::fastをxf::cv::fastで置き換えてみた話。
単純な置き換えで並列化もしてないために更に遅くなった。
間引き処理まで含めて一度最適化してみようかとは思う。

xf::cv::fastは8の倍数の列数をカーネルに指定しないと応答が帰ってこなくなる模様。
XF_NPPC1をNPSに指定していれば大丈夫と考えていたが、実際に動作させてみるとenqueueReadBufferか、 enqueueTaskのイベントが完了しなくなる事象を確認した。
8の倍数を指定すると正常にイベントが完了するのか、処理が先に進む。 面倒なので原因は追って無いが、enqueueTasの完了条件満たせなくなるのだろうと思っている。
なので、オリジナルの実装から少し変更し、固定サイズセルに分割するように変更した。 この辺はACRiの記事と同じかな。

また、orb_slam2ではcv::fast処理を行って得られたkeypointのresponse値を使用して特徴点の間引きを行っているが、 xf::cv::fastはkeypointが得られず、response値も得られない実装となっている。 とりあえずは動作速度の確認のために検出したコーナをkeypoint化し、response値は埋めないように実装して試した。

keypointの差はどうやって埋めようかなぁ。

環境

  • 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ブランチ)

環境

省略。

sw_emu

インターフェースのデバッグにはvitis -debugが有効だった。
setArgは変更毎に実行しないとカーネルに設定されないことはこれで見つけた。
以下に実行した方法を示しておく。

build

hashは50ac9c83379795185fd49166ca9d1c074b37dc23。
hashはb35f2dde90e18fd94b08c4ce903f16866f9797dd。

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=ON -DBUILD_FAST_TEST=ON -DDISABLE_RESIZE_KRNL=ON -DDISABLE_FAST_KRNL=OFF
ninja -j4

run

-forward-portオプションは1つのポートしか指定できない模様(v2020.2では)。 なので、sshのポートにビルドPC側の2222番ポートでアクセスできるようにしておく。

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

エミュレータ起動したらtcfが1534番のポートで待ち受けているので、 ビルドPC側の1440番ポートで接続できるようにsshでtargetに接続する。

ssh -L 1440:localhost:1534 localhost -p 2222 -l root

テスト対象を転送する。(リポジトリのルートからの実行) orb_slam2_ros_mono_tum_testは転送しなくてもvitisがやってくれるかも。

ssh -p 2222 root@localhost "mkdir -p /usr/bin/xclbin"
scp -P 2222 build/orb_slam2_ros_mono_tum_test root@localhost:/home/root/
scp -P 2222 orb_slam2/lib/liborb_slam2_ros_core.so root@localhost:/usr/lib/liborb_slam2_ros_core.accel.so
scp -P 2222 build/hw/hw_link/orbslam2_accel_sw_emu.xclbin root@localhost:/usr/bin/xclbin/resize_krnl.xclbin

エミュレータ実行フォルダから次の通り実行する。

vitis -debug -flow embedded_accel -host-exe-file ../../../orb_slam2_ros_mono_tum_test -target sw_emu -kernel-names fast_accel -program-args "/usr/share/orb_slam2_ros/orb_slam2/Vocabulary/ORBvoc.txt /home/root/tum-dataset" -host 127.0.0.1 -port 1440

result

デバッグ画面表示されるのと、ブレークポイント設定することでカーネル呼び出し時の引数の状態などを確認できる。
ライブラリの中までデバッグしようとした場合にはどうすればよいかはよく分からない。
hostプログラムだけならgdbserverとdebugfsを用意すればできる。

hw

resize_krnlとfast_krnlを両方活かしてみてどうなるかを確認する。

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=hw -DCMAKE_BUILD_TYPE=Debug -DENABLE_KRNL_CHECK=OFF -DBUILD_FAST_TEST=ON -DDISABLE_RESIZE_KRNL=OFF -DDISABLE_FAST_KRNL=OFF
ninja -j4

run

テスト対象を転送する。

ssh root@192.168.2.1 "mkdir -p /usr/bin/xclbin"
scp build/orb_slam2_ros_mono_tum_test root@192.168.2.1:/home/root/
scp orb_slam2/lib/liborb_slam2_ros_core.so root@192.168.2.1:/usr/lib/liborb_slam2_ros_core.accel.so
scp build/hw/hw_link/orbslam2_accel_hw.xclbin root@192.168.2.1:/usr/bin/xclbin/resize_krnl.xclbin
root@ultra96v2-zynqmp:~# export LD_LIBRARY_PATH=/mnt/sd-mmcblk0p1:/tmp:$LD_LIBRARY_PATH
root@ultra96v2-zynqmp:~# export XILINX_XRT=/usr
root@ultra96v2-zynqmp:~# export XILINX_VITIS=/mnt/sd-mmcblk0p1
root@ultra96v2-zynqmp:~# mv /usr/lib/liborb_slam2_ros_core.so /usr/lib/liborb_slam2_ros_core.soft.so
root@ultra96v2-zynqmp:~# ln -s -f /usr/lib/liborb_slam2_ros_core.accel.so /usr/lib/liborb_slam2_ros_core.so
root@ultra96v2-zynqmp:~# time ./orb_slam2_ros_mono_tum_test /usr/share/orb_slam2_ros/orb_slam2/Vocabulary/ORBvoc.txt ./tum-dataset

result

liborb_slam2_ros_core.soft.soを使用する場合はmedian tracking=0.12、トータル約2分なので、倍くらいの時間がかかるようになった。
置き換えただけじゃ当然そうなるよね。

root@ultra96v2-zynqmp:~# time ./orb_slam2_ros_mono_tum_test /usr/share/orb_slam2_ros/orb_slam2/Vocabulary/ORBvoc.txt ./tum-dataset

ORB-SLAM2 Copyright (C) 2014-2016 Raul Mur-Artal, University of Zaragoza.
This program comes with ABSOLUTELY NO WARRANTY;
This is free software, and you are welcome to redistribute it
under certain conditions. See LICENSE.txt.

OpenCV version : 3.4.3
Major version : 3
Minor version : 4
Subminor version : 3
Input sensor was set to: Monocular

Loading ORB Vocabulary.
Vocabulary loaded!


Camera Parameters: 
- fx: 517.306
- fy: 516.469
- cx: 318.643
- cy: 255.314
- k1: 0.262383
- k2: -0.953104
- k3: 0.002628
- p1: 1.16331
- p2: -0.005358
- fps: 30
- bf: 0
- color order: RGB (ignored if grayscale)
Found Platform
Platform Name: Xilinx
INFO: Device found - edge
Loading: '/usr/bin/xclbin/resize_krnl.xclbin'
Found Platform
Platform Name: Xilinx
INFO: Device found - edge
Loading: '/usr/bin/xclbin/resize_krnl.xclbin'

ORB Extractor Parameters: 
- Number of Features: 1000
- Scale Levels: 8
- Scale Factor: 1.2
- Initial Fast Threshold: 20
- Minimum Fast Threshold: 7

-------
Start processing sequence ...
Images in the sequence: 798

-------

median tracking time: 0.259621
mean tracking time: 0.258882

Saving keyframe trajectory to KeyFrameTrajectory.txt ...

trajectory saved!

real    3m53.420s
user    3m24.638s
sys 0m45.453s
root@ultra96v2-zynqmp:~# 

0 件のコメント:

コメントを投稿