2021年5月28日金曜日

enqueueMigrateMemObjectを使ってみたときのメモ

enqueueMigrateMemObjectを使ってみたときのメモ

使い方

1.cl::Bufferを宣言する

hostが書き込む場合はCL_MEM_READ_ONLYのflagを指定する。
hostが読み込む場合はCL_MEM_WRITE_ONLYのflagを指定する。
exampleには無いが、ドキュメントではCL_MEM_ALLOC_HOST_PTRを使う方が良いらしい。

cl::Buffer *imageToDevice_fast;
cl::Buffer *buffer_vec;
imageToDevice_fast = new cl::Buffer(*context, CL_MEM_READ_ONLY | CL_MEM_ALLOC_HOST_PTR, fast_and_dist_in_size_bytes, NULL, &err);
buffer_vec = new cl::Buffer(*context, CL_MEM_WRITE_ONLY | CL_MEM_ALLOC_HOST_PTR, vector_size, NULL, &err);

2.Kernelにcl::Bufferを紐付ける

cl::Kernel *fast_krnl;
fast_krnl = new cl::Kernel(program,"fast_and_dist_accel", &err);
fast_krnl->setArg(0, *imageToDevice_fast);
fast_krnl->setArg(4, *buffer_vec);

3.cl::Bufferのポインタを取得する

unsigned char *host_write_ptr_fast;
host_write_ptr_fast = (unsigned char *)q->enqueueMapBuffer(*imageToDevice_fast,CL_TRUE,CL_MAP_WRITE,0,rows_fast*cols_fast*sizeof(unsigned char),nullptr,nullptr,&err);
kernel_write_ptr_fast = (unsigned int *)q->enqueueMapBuffer(*buffer_vec,CL_TRUE,CL_MAP_READ,0,vector_size,nullptr,nullptr,&err);

4.書き込む場合は取得したポインタを使用してcl::Bufferを操作する

for(int k=0; k < rows_fast; ++k){
    memcpy( (host_write_ptr_fast + k*buffer_row_pitch),
            (img_ptr + (k+(unsigned int)iniY)*host_row_pitch + (unsigned int)iniX),
            buffer_row_pitch);
}

5.enqueueMigrateMemObjectsでcl::Bufferを指定する。

q->enqueueMigrateMemObjects({*imageToDevice_fast},0,nullptr, &write_event);

6.読み出す場合はenqueueMigrateMemObjectsの実行後にポインタを介してデータ取得する。

if((kernel_write_ptr_fast[ii] & 0x80000000) != 0){
    // statements
}

感想

KernelにBufferを紐付けるのは最後でも良い気がする。 そうすれば前処理したデータをcl::Bufferとしてたくさん持っておいて、 これを逐次切り替えながらkernelを動作させるということも可能そう。

2021年5月21日金曜日

ultra96v2でVitis 2020.2を使用してORB_SLAM2のFASTとDistirbuteOctTree処理をカーネル化していく話その3

fastとcomputeDistributeOctTreeを一つにしたfast_and_distカーネルを作っていく話その3。

入力画像をcloneしてenqueueWriteBufferに突っ込んでいる所がすごく気になっていたので改善方法探ったら、
enqueueWriteBufferRectのメソッドがあったのでこれを使ってみたところ少し改善した。
また、同時にカーネル側も改造し、フィルタ機能を追加した。

変更内容

hostプログラムの変更

2021/5/26 下記は初回の転送だけしか行われないよう。テストしたつもりだったが、その後は動作確認できないので、結局はenqueueMigrateMemObjectを使った方法に変更することとなった。

buffer_originはFPGAに確保したメモリ上の転送先を{x,y,z}の配列で指定する。
カーネルの転送先は原点を指定したいので{0,0,0}

host_originはホストメモリ上の転送元を{x,y,z}の配列で指定する。
hostにある解析対象画像のFASTによって特徴点抽出した上で間引き処理したい部分の開始地点を指定する。
2次元の場合はz=0を指定する必要がある。

regionは矩形領域のサイズを{x,y,z}の配列で指定する。
2次元の場合はz=1を指定する必要がある。

buffer_row_pitchはカーネルの1行の長さを指定する。
buffer_slice_pitchは3次元の場合に使う模様。今回は2次元なので0。

host_row_pitchは元画像の1行の長さを指定する。 host_slice_pitchも同様。こちらも0。

ptrはhost上のメモリにある画像のポインタを指定する。


array<size_t,3> host_origin = {	(((unsigned int)iniX) * sizeof(unsigned char)),
										(((unsigned int)iniY) * sizeof(unsigned char)),
										0}; // should be 0 in 2d.
array<size_t,3> region = {	cols_fast * sizeof(unsigned char),
									rows_fast * sizeof(unsigned char),
                                    1};
size_t buffer_row_pitch = cols_fast * sizeof(unsigned char);
size_t host_row_pitch = mvImagePyramid[level].cols * sizeof(unsigned char);

err = q->enqueueWriteBufferRect(	*imageToDevice_fast,        // buffer on the FPGA
									CL_TRUE,                    // blocking call
                                    {0,0,0},                    // size_t<3> buffer offset in bytes
                                    host_origin,                // size_t<3> host offset in bytes
                                    region,                     // size_t<3> region
                                    buffer_row_pitch,           // size_t buffer_row_pitch
                                    0,                          // size_t buffer_slice_pitch
                                    host_row_pitch,             // size_t host_row_pitch
                                    0,                          // size_t host_slice_pitch
                                    mvImagePyramid[level].data, // Pointer to the data to copy
                                    nullptr, &event);

カーネルの変更

フレームを4分割したサブフレームでの最大値を探索して、最後に結果を出力する。
メモリアクセスのコスト下げるためにコーナースコアは最終ワードにまとめた。
気休めだと思うけどレジスタに配置されるよう個別に宣言して全てif文で比較する。

コードは以下の通り。

#include "xf_fast_and_dist_config.h"

template <int PW, int SRC_T, int ROWS, int COLS, int NPC>
void fastResult2Vec(xf::cv::Mat<SRC_T, ROWS, COLS, NPC>& in_img, ap_uint<32>* vec_out){

    int read_index = 0;
    ap_uint<32> vec0 = 0;
    ap_uint<32> vec_resp0 = 0;
    ap_uint<32> vec1 = 0;
    ap_uint<32> vec_resp1 = 0;
    ap_uint<32> vec2 = 0;
    ap_uint<32> vec_resp2 = 0;
    ap_uint<32> vec3 = 0;
    ap_uint<32> vec_resp3 = 0;

    for (int row = 0; row < in_img.rows; row++) {
#pragma HLS PIPELINE
        for (int col = 0; col < in_img.cols; col++) {
            ap_uint<8> temp = in_img.read(read_index++);
            if(temp != 0){
                if ((col <= in_img.cols/2) && (row <= in_img.rows/2) && (temp > vec_resp0)){vec0 = 0x80000000 + (row << 15) + col; vec_resp0 = temp;}
                if ((col >  in_img.cols/2) && (row <= in_img.rows/2) && (temp > vec_resp1)){vec1 = 0x80000000 + (row << 15) + col; vec_resp1 = temp;}
                if ((col <= in_img.cols/2) && (row >  in_img.rows/2) && (temp > vec_resp2)){vec2 = 0x80000000 + (row << 15) + col; vec_resp2 = temp;}
                if ((col >  in_img.cols/2) && (row >  in_img.rows/2) && (temp > vec_resp3)){vec3 = 0x80000000 + (row << 15) + col; vec_resp3 = temp;}
            }
        }
    }
#ifndef __SYNTHESIS__
    std::cout << std::dec;
    std::cout << "rows,cols:" << in_img.rows << "," << in_img.cols << std::endl;
    std::cout << "vec0:" << std::hex << vec0 << std::endl;
    std::cout << "vec1:" << std::hex << vec1 << std::endl;
    std::cout << "vec2:" << std::hex << vec2 << std::endl;
    std::cout << "vec3:" << std::hex << vec3 << std::endl;
    std::cout << "vec4:" << std::hex << ((vec_resp3 << 24) + (vec_resp2 << 16) + (vec_resp1 << 8) + vec_resp0) << std::endl;
#endif
    vec_out[0] = vec0;
    vec_out[1] = vec1;
    vec_out[2] = vec2;
    vec_out[3] = vec3;
    vec_out[4] = (vec_resp3 << 24) + (vec_resp2 << 16) + (vec_resp1 << 8) + vec_resp0;
    return;
}

extern "C" {

void fast_and_dist_accel(   ap_uint<PTR_WIDTH>* img_in, unsigned char threshold, /*ap_uint<PTR_WIDTH>* img_out,*/ int rows, int cols,
                            ap_uint<32>* vec_out) {
// clang-format off
    #pragma HLS INTERFACE m_axi      port=img_in        offset=slave  bundle=gmem0
    
//    #pragma HLS INTERFACE m_axi      port=img_out       offset=slave  bundle=gmem1
    #pragma HLS INTERFACE m_axi      port=vec_out       offset=slave  bundle=gmem0
    #pragma HLS INTERFACE s_axilite  port=rows
    #pragma HLS INTERFACE s_axilite  port=cols
    #pragma HLS INTERFACE s_axilite  port=threshold
    #pragma HLS INTERFACE s_axilite  port=return
    // clang-format on

    xf::cv::Mat<TYPE, HEIGHT, WIDTH, NPC1> imgInput(rows, cols);
    xf::cv::Mat<TYPE, HEIGHT, WIDTH, NPC1> imgOutput(rows, cols);
// clang-format off
    #pragma HLS DATAFLOW
    // clang-format on

    // Retrieve xf::cv::Mat objects from img_in data:
    xf::cv::Array2xfMat<PTR_WIDTH, TYPE, HEIGHT, WIDTH, NPC1>(img_in, imgInput);

    // Run xfOpenCV kernel:
    xf::cv::fast<NMS, TYPE, HEIGHT, WIDTH, NPC1>(imgInput, imgOutput, threshold);

    // Convert _dst xf::cv::Mat object to output array:
    //xf::cv::xfMat2Array<PTR_WIDTH, TYPE, HEIGHT, WIDTH, NPC1>(imgOutput, img_out);

    // Convert _dst xf::cv::Mat objecto to output vector
    fastResult2Vec<PTR_WIDTH, TYPE, HEIGHT, WIDTH, NPC1>(imgOutput, vec_out);

    return;
} // End of kernel

} // End of extern C

result

https://github.com/akira-nishiyama/orb_slam_2_ros.gitのfeature-fpgaブランチのhash:47ca7053e207f37d705f47d570360982ccc0743fをビルド・実行すると、以下の結果が得られる。
少し改善したが、劇的には変わらない。

root@ultra96v2-zynqmp:~# time ./orb_slam2_ros_mono_tum_test /usr/share/orb_slam2_ros/orb_slam2/Vocabulary/ORBvoc.txt /home/root/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'
program xclbin.
program xclbin Done.
create resize_accel kernel.
create resize_accel kernel Done.
Found Platform
Platform Name: Xilinx
INFO: Device found - edge
Loading: '/usr/bin/xclbin/resize_krnl.xclbin'
program xclbin.
program xclbin Done.
create resize_accel kernel.
create resize_accel kernel Done.

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.170544
mean tracking time: 0.170566

Saving keyframe trajectory to KeyFrameTrajectory.txt ...

trajectory saved!

real    2m42.178s
user    2m5.889s
sys 0m25.341s

2021年5月14日金曜日

ultra96v2でVitis 2020.2を使用してORB_SLAM2のFASTとDistirbuteOctTree処理をカーネル化していく話その2

続けて間引き処理をカーネルに追加していく。

フレームを4分割したサブフレームでの最大値を探索して、最後に結果を出力する。
メモリアクセスのコスト下げるためにコーナースコアは最終ワードにまとめた。
気休めだと思うけどレジスタに配置されるよう個別に宣言して全てif文で比較する。
カーネルの探索範囲を40x40の領域に限定すると32bitに全ての情報載せられそうだけど、改善は微々たるものと思うのでとりあえず保留。

カーネル部分のコードは以下の通り。

#include "xf_fast_and_dist_config.h"

template <int PW, int SRC_T, int ROWS, int COLS, int NPC>
void fastResult2Vec(xf::cv::Mat<SRC_T, ROWS, COLS, NPC>& in_img, ap_uint<32>* vec_out){

    int read_index = 0;
    ap_uint<32> vec0 = 0;
    ap_uint<8> vec_resp0 = 0;
    ap_uint<32> vec1 = 0;
    ap_uint<8> vec_resp1 = 0;
    ap_uint<32> vec2 = 0;
    ap_uint<8> vec_resp2 = 0;
    ap_uint<32> vec3 = 0;
    ap_uint<8> vec_resp3 = 0;

    for (int row = 0; row < in_img.rows; row++) {
#pragma HLS PIPELINE
        for (int col = 0; col < in_img.cols; col++) {
            ap_uint<8> temp = in_img.read(read_index++);
            if(temp != 0){
                if ((col <= COLS/2) && (row <= ROWS/2) && (temp > vec0)){vec0 = 0x80000000 + (row << 15) + col; vec_resp0 = temp;}
                if ((col >  COLS/2) && (row <= ROWS/2) && (temp > vec1)){vec1 = 0x80000000 + (row << 15) + col; vec_resp1 = temp;}
                if ((col <= COLS/2) && (row >  ROWS/2) && (temp > vec2)){vec2 = 0x80000000 + (row << 15) + col; vec_resp2 = temp;}
                if ((col >  COLS/2) && (row >  ROWS/2) && (temp > vec3)){vec3 = 0x80000000 + (row << 15) + col; vec_resp3 = temp;}
            }
        }
    }
    vec_out[0] = vec0;
    vec_out[1] = vec1;
    vec_out[2] = vec2;
    vec_out[3] = vec3;
    vec_out[4] = (vec_resp3 << 24) + (vec_resp2 << 16) + (vec_resp1 << 8) + vec_resp0;
    return;
}

extern "C" {

void fast_and_dist_accel(   ap_uint<PTR_WIDTH>* img_in, unsigned char threshold, /*ap_uint<PTR_WIDTH>* img_out,*/ int rows, int cols,
                            ap_uint<32>* vec_out) {
// clang-format off
    #pragma HLS INTERFACE m_axi      port=img_in        offset=slave  bundle=gmem0
    
//    #pragma HLS INTERFACE m_axi      port=img_out       offset=slave  bundle=gmem1
    #pragma HLS INTERFACE m_axi      port=vec_out       offset=slave  bundle=gmem1
    #pragma HLS INTERFACE s_axilite  port=rows
    #pragma HLS INTERFACE s_axilite  port=cols
    #pragma HLS INTERFACE s_axilite  port=threshold
    #pragma HLS INTERFACE s_axilite  port=return
    // clang-format on

    xf::cv::Mat<TYPE, HEIGHT, WIDTH, NPC1> imgInput(rows, cols);
    xf::cv::Mat<TYPE, HEIGHT, WIDTH, NPC1> imgOutput(rows, cols);
// clang-format off
    #pragma HLS DATAFLOW
    // clang-format on

    // Retrieve xf::cv::Mat objects from img_in data:
    xf::cv::Array2xfMat<PTR_WIDTH, TYPE, HEIGHT, WIDTH, NPC1>(img_in, imgInput);

    // Run xfOpenCV kernel:
    xf::cv::fast<NMS, TYPE, HEIGHT, WIDTH, NPC1>(imgInput, imgOutput, threshold);

    // Convert _dst xf::cv::Mat object to output array:
    //xf::cv::xfMat2Array<PTR_WIDTH, TYPE, HEIGHT, WIDTH, NPC1>(imgOutput, img_out);

    // Convert _dst xf::cv::Mat objecto to output vector
    fastResult2Vec<PTR_WIDTH, TYPE, HEIGHT, WIDTH, NPC1>(imgOutput, vec_out);

    return;
} // End of kernel

} // End of extern C

ビルドは以下の通り。hashはfcf6cdc2661a448b21190a7dd9b710e9b507f545

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=<path-to-sd-root> -DPLATFORM_COMPONENTS_PATH=<path-to-components> -DBUILD_TEST_TARGETS=OFF -DBUILD_TARGET=hw -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

実行結果は次の通り。
時間はそこそこ短くなったけど全然及ばないなぁ。
hostプログラムのclone処理が悪いと思うが。。。

root@ultra96v2-zynqmp:~# time ./orb_slam2_ros_mono_tum_test /usr/share/orb_slam2_ros/orb_slam2/Vocabulary/ORBvoc.txt /home/root/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'
file size:5625745
actual read size:5625745
program xclbin.
program xclbin Done.
create resize_accel kernel.
create resize_accel kernel Done.
Found Platform
Platform Name: Xilinx
INFO: Device found - edge
Loading: '/usr/bin/xclbin/resize_krnl.xclbin'
file size:5625745
actual read size:5625745
program xclbin.
program xclbin Done.
create resize_accel kernel.
create resize_accel kernel Done.

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.188161
mean tracking time: 0.188687

Saving keyframe trajectory to KeyFrameTrajectory.txt ...

trajectory saved!

real    2m56.512s
user    2m35.888s
sys 0m55.475s

2021年5月13日木曜日

ultra96v2でVitis 2020.2を使用してORB_SLAM2のFASTとDistirbuteOctTree処理をカーネル化していく話

fastとcomputeDistributeOctTreeを一つにしたfast_and_distカーネルを作っていく話。
アクセラレータにDistribution機能を移すに際して、アルゴリズムを変更し、動作確認を行った。

環境

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

変更内容

現状のcomputeDistributeOctTreeは全ての特徴点を分割したノードに割付ていき、
分割の限界となった場合には、各々のノードで最も明確な特徴点を残し、残りは削除して処理を終了する。
または、各ノードに一つの特徴点が配置された状態となった場合に処理を終了する。
(https://www.acri.c.titech.ac.jp/wordpress/archives/7776)

これをHW処理しやすいようにノードサイズをFASTの抽出単位と揃えて固定し、そのノードを更に4分割し、
4分割ノードそれぞれで最も明確な特徴点を選出して間引くこととした。
最小ノードのサイズが同じであれば、ほぼ同じ結果が得られることが期待される。

考え方はおおよそACRiの記事と同じ。
一方でそのままだとultra96v2には乗らないので、改変する。
アルゴリズムは細かく書くと次の通りとなる。

(1)フレームを規定のサイズに分割する。(とりあえずは40x40)
(2)各フレームのFAST特徴点をiniThFASTのしきい値で抽出する。
(3)特徴点が見つからない場合にはminThFASTのしきい値で抽出する。
(4)得られた特徴点はフレームを4分割したサブフレームに割付け、サブフレームで最も明確な特徴点を一つ選び出す。

試してみるとtum-datasetでは同一頂点が抽出されるので問題無く使用できると考えられる。2つのしきい値を同時にチェックする方法もHWコストの割に高速化に効きそうなので考えておく。

build

まずはカーネルを使用せずに評価してみる。
-DDISABLE_NEW_DISTRIBUTION=OFF -DENABLE_KRNL_CHECK=ONとすると変更前後を比較して結果を標準出力するようになる。
また、-DDISABLE_NEW_DISTRIBUTION=ON -DENABLE_KRNL_CHECK=OFFとすると、オリジナルコードに近い状態で動作する。  

hashは2d04944a46ee3d2c71e5c108a376b92a5655770cで確認。

2021/5/20:比較が間違っていたので修正版を作成中

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=<path-to-sd-root> -DPLATFORM_COMPONENTS_PATH=<path-to-components> -DBUILD_TEST_TARGETS=OFF -DBUILD_TARGET=hw -DCMAKE_BUILD_TYPE=Debug -DENABLE_KRNL_CHECK=ON -DBUILD_FAST_TEST=OFF -DBUILD_FAST_AND_DIST_TEST=ON -DDISABLE_RESIZE_KRNL=ON -DDISABLE_FAST_KRNL=ON -DDISABLE_NEW_DISTRIBUTION=OFF

result

変更後

root@ultra96v2-zynqmp:~# time ./orb_slam2_ros_mono_tum_test /usr/share/orb_slam2_ros/orb_slam2/Vocabulary/ORBvoc.txt /home/root/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'
file size:5634881
actual read size:5634881
program xclbin.
program xclbin Done.
create resize_accel kernel.
create resize_accel kernel Done.
Found Platform
Platform Name: Xilinx
INFO: Device found - edge
Loading: '/usr/bin/xclbin/resize_krnl.xclbin'
file size:5634881
actual read size:5634881
program xclbin.
program xclbin Done.
create resize_accel kernel.
create resize_accel kernel Done.

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.0999473
mean tracking time: 0.0991993

Saving keyframe trajectory to KeyFrameTrajectory.txt ...

trajectory saved!

real    1m45.135s
user    1m54.849s
sys 0m5.194s
real    1m43.408s
user    1m55.425s
sys 0m4.890s

オリジナル

実行時間だけ書いておく。
少し早くなっているかな?

real    2m1.869s
user    2m13.626s
sys 0m5.523s
real    2m0.575s
user    2m13.668s
sys 0m5.611s

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

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:~#