2022年7月15日金曜日

ros2のpendulum_demoを実行してみた話

ros2のpendulum_demo[https://github.com/ros2/demos/tree/master/pendulum_control]を実行してみたときのメモ。

環境

ホスト環境

OS:PROXMOX VE 7.2
CPU:intel core i7 -11800H
Mem:16GB

ゲスト環境

OS:Ubuntu 22.04
CPU:8vCPU
Mem:12GB
非リアルタイムカーネル使用

pendulum_demoの実行

まずはそのまま実行してみる。

anishiyama@ubuntu-ros2:~/ros2/humble$ source ./install/setup.sh 
anishiyama@ubuntu-ros2:~/ros2/humble$ pendulum_demo 
Couldn't set scheduling priority and policy: Operation not permitted
Caught exception: std::bad_alloc
Unlocking memory and continuing.
Couldn't lock all cached virtual memory.
Pagefaults from reading pages not yet mapped into RAM will be recorded.
Initial major pagefaults: 0
Initial minor pagefaults: 315622
No results filename given, not writing results
rttest statistics:
  - Minor pagefaults: 0
  - Major pagefaults: 0
  Latency (time after deadline was missed):
    - Min: 57384 ns
    - Max: 210201 ns
    - Mean: 90464.533000 ns
    - Standard deviation: 25207.301195
PendulumMotor received 496 messages
PendulumController received 495 messages

いくつかメッセージが確認できるので、 readmeに従い/etc/security/limits.confを編集する。 同時にpriorityも98まで設定できるようにする。 実行ユーザがanisiyamaなので、次の記述を追加した。

anishiyama      -       memlock         10000000
anishiyama      -       rtprio          98

ログインし直して再実行。 メッセージはいくつか消えた。 仮想環境なためか、実行レイテンシは大きめ。

anishiyama@ubuntu-ros2:~/ros2/humble$ pendulum_demo 
Initial major pagefaults: 0
Initial minor pagefaults: 2124626
No results filename given, not writing results
rttest statistics:
  - Minor pagefaults: 0
  - Major pagefaults: 0
  Latency (time after deadline was missed):
    - Min: 8947 ns
    - Max: 224184 ns
    - Mean: 51156.345000 ns
    - Standard deviation: 29789.714229


PendulumMotor received 498 messages
PendulumController received 493 messages

2022年7月3日日曜日

ros2でカスタムパッケージをros2 coreコンテナで動作させてみた話

ros2 nodeのdockerコンテナ運用について考えてみる。
docker環境で動作させる記事は公式のチュートリアルに 紹介されているが、ビルド環境も一緒に動かしているので、 ros2のcore部分だけで動作させる方法を確認した。

実行方法

dockerインストール後に次の通り実行すれば良い。

$ git clone https://github.com/akira-nishiyama/build_ros2_exec_container_example.git
$ cd build_ros2_exec_container_example
$ docker-compose build
$ docker-compose up

実行結果

Starting env_listener_1 ... done
Starting env_talker_1   ... done
Attaching to env_talker_1, env_listener_1
talker_1    | [INFO] [1656748948.461309414] [minimal_publisher]: Publishing: "Hello World: 0"
talker_1    | [INFO] [1656748948.947667336] [minimal_publisher]: Publishing: "Hello World: 1"
talker_1    | [INFO] [1656748949.447749747] [minimal_publisher]: Publishing: "Hello World: 2"
talker_1    | [INFO] [1656748949.947751669] [minimal_publisher]: Publishing: "Hello World: 3"
talker_1    | [INFO] [1656748950.447781256] [minimal_publisher]: Publishing: "Hello World: 4"
talker_1    | [INFO] [1656748950.947751269] [minimal_publisher]: Publishing: "Hello World: 5"
talker_1    | [INFO] [1656748951.447926078] [minimal_publisher]: Publishing: "Hello World: 6"
listener_1  | [INFO] [1656748951.586250380] [minimal_subscriber]: I heard: "Hello World: 6
talker_1    | [INFO] [1656748951.947916486] [minimal_publisher]: Publishing: "Hello World: 7"
listener_1  | [INFO] [1656748951.948192281] [minimal_subscriber]: I heard: "Hello World: 7
talker_1    | [INFO] [1656748952.447858693] [minimal_publisher]: Publishing: "Hello World: 8"
listener_1  | [INFO] [1656748952.448205040] [minimal_subscriber]: I heard: "Hello World: 8
talker_1    | [INFO] [1656748952.947910963] [minimal_publisher]: Publishing: "Hello World: 9"
listener_1  | [INFO] [1656748952.948246575] [minimal_subscriber]: I heard: "Hello World: 9

環境

ホスト環境

OS:PROXMOX VE 7.2
CPU:intel core i7 -11800H
Mem:16GB

ゲスト環境

OS:Ubuntu 22.04
CPU:8vCPU
Mem:12GB

docker環境

base:Ubuntu 22.04
ros2:humble

内容

Dockerfile

まず最初にbuild対象パッケージをros2 build環境(docker)に取り込む。
対象パッケージの動作確認は予め済ませておくこと。
方法は
1.ホスト環境のパッケージを直接取り込む
2.vcstoolを使ってgitリポジトリから収集する
が良さそうかな。
バージョン管理考えるとgitリポジトリ使う方が良さそうだけど、 外部リポジトリ参照したり、パッケージとして使ってもらわない場合は今回のリポジトリのようにDockerfile等と合わせての管理も簡単そう。
該当箇所は次の通り。

################################
# multi-stage for build
################################
FROM ros:humble-ros-base-jammy as build
#project workspace
ARG PRJ_WS=/workspace/install
ARG TMP_WS=/tmp
WORKDIR $TMP_WS

# import project
# copy from host directory.
COPY ./project/src $TMP_WS/src
## clone using vcstool is also ok.
##(see https://github.com/dirk-thomas/vcstool for detail)
#RUN echo "\
#repositories: \n\
#  ros2/demos: \n\
#    type: git \n\
#    url: https://github.com/ros2/demos.git \n\
#    version: ${ROS_DISTRO} \n\
#" > ./project.repos
#RUN vcs import ./src < ./project.repos

PRJ_WSがros2実行環境の配置場所で、TMP_WSがbuild時の作業スペースとなっている。 ソースの収集が終わったあとは依存性の解決を行う。きちんとパッケージ収集すれば不要なのと、root権限で実行しているのでwarningが非常に気になってしまうから、無くても良い気はしている。必要なもの分かっていればaptで指定して揃える方が良さそう。

# install rosdep
RUN apt-get update && apt-get install -y --no-install-recommends python3-rosdep

# resolve dependency
RUN rosdep update && rosdep install -y --from-paths $TMP_WS/src

依存性を解決し終えたらbuildを行う。 installフォルダだけをros2実行環境に引き継ぐために–install-baseオプションを使用する。

# build
RUN colcon build --install-base $PRJ_WS

build完了したので、次はros2実行環境のセットアップを行う。
ros2 build環境からinstallデータだけを引き継ぐ。

################################
# multi-stage for exec
################################
FROM ros:humble-ros-core-jammy as exec
#project workspace
ARG PRJ_WS=/workspace/install
WORKDIR $PRJ_WS
# import artifacts
COPY --from=build $PRJ_WS $PRJ_WS

その後依存性を解決させるためにrosdepを使用する。 package.xmlあったと思うので、多分有効なはず。(動作未確認)
ダメならソースも実行環境に引き継いでおけば良い。

# install rosdep
RUN apt-get update && apt-get install -y --no-install-recommends python3-rosdep

# resolve dependency
RUN rosdep init && rosdep update \
        && rosdep install -y --from-paths $PRJ_WS \
        && apt-get remove -y python3-rosdep \
        && apt-get -y clean \
        && rm -rf /var/lib/apt/lists/*

最後に実行時の環境セットアップを行う。 環境変数の設定と、実行時にintall/local_setup.shを呼び出すようにros_entrypoint.shを編集する。 実行時のコマンドはlaunchに差し替えても良い。

# source entrypoint setup
ENV PRJ_WS $PRJ_WS
RUN sed --in-place --expression \
    '$isource "$PRJ_WS/local_setup.sh"' \
    /ros_entrypoint.sh

CMD ["ros2", "run", "py_pubsub", "talker"]
#CMD ["bash"]

docker-compose

talkerとlistenerを別々のコンテナで起動させて通信させている。

version: '2'

services:
  talker:
    build: ./context
    image: py_pubsub:latest
    command: ros2 run py_pubsub talker
  listener:
    build: ./context
    image: py_pubsub:latest
    command: ros2 run py_pubsub listener

2022年1月1日土曜日

単精度浮動小数点での行列積の性能を評価してみた話

単精度浮動小数点での行列積の性能を評価する方法を調べた際のメモ。
ベンチマークにはHPL-AI使う方が良いかもしれない。

環境

PC:DELL Inspiron 16
CPU:11th Gen Intel® Core™ i7-11800H @ 2.30GHz × 16
GPU: NVIDIA GeForce RTX 3050 Laptop GPU/4GB/gen4?
Mem:16G
OS:Ubuntu 20.04LTS

評価方法

C=ABを計算する時間を計測する。 また、openblasによる計算結果との差がepsilon()以下であることも確認する。

リポジトリをクローンして、jupyter notebookをすべて実行すると結果が得られる。 gcc,cmake,make,openmp,openblas,cudaが必要。

結果

次のグラフの通り。
単純Cループと比較するとOpenBLASはやはりすごい。
行列サイズが大きくなってくるとcublasの効果が際立ってくる。


参考ページ

行列の積演算で openBLAS cuBLAS を体感する
cuBLAS と cuBLAS-XT の調査(その1)。行列の積演算にて
[VC++] OpenBLASを使ってみた

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