The idea of the camera course is to build a collision detection system - that's the overall goal for the Final Project. As a preparation for this, you will now build the feature tracking part and test various detector / descriptor combinations to see which ones perform best. This mid-term project consists of four parts:
- First, you will focus on loading images, setting up data structures and putting everything into a ring buffer to optimize memory load.
- Then, you will integrate several keypoint detectors such as HARRIS, FAST, BRISK and SIFT and compare them with regard to number of keypoints and speed.
- In the next part, you will then focus on descriptor extraction and matching using brute force and also the FLANN approach we discussed in the previous lesson.
- In the last part, once the code framework is complete, you will test the various algorithms in different combinations and compare them with regard to some performance measures.
See the classroom instruction and code comments for more details on each of these parts. Once you are finished with this project, the keypoint matching part will be set up and you can proceed to the next lesson, where the focus is on integrating Lidar points and on object detection using deep-learning.
- cmake >= 2.8
- All OSes: click here for installation instructions
- make >= 4.1 (Linux, Mac), 3.81 (Windows)
- Linux: make is installed by default on most Linux distros
- Mac: install Xcode command line tools to get make
- Windows: Click here for installation instructions
- OpenCV >= 4.1
- This must be compiled from source using the
-D OPENCV_ENABLE_NONFREE=ON
cmake flag for testing the SIFT and SURF detectors. - The OpenCV 4.1.0 source code can be found here
- This must be compiled from source using the
- gcc/g++ >= 5.4
- Linux: gcc / g++ is installed by default on most Linux distros
- Mac: same deal as make - install Xcode command line tools
- Windows: recommend using MinGW
- Clone this repo.
- Make a build directory in the top level directory:
mkdir build && cd build
- Compile:
cmake .. && make
- Run it:
./2D_feature_tracking
.
- I added code for variuos opencv algorithms for - keypoint detectors, descriptor, and matchers from two consecutive images.
- I used KNN match selection (k=2) and performed descriptor distance ratio filtering with t=0.8 in file
matching2D.cpp
. - Created test results by running combination of algorithms for - keypoint detectors, descriptor, and matchers against KITTI images.
-
Added new code to capture KPI, metrics from various experiments (with combinations of alogrithms detectors, descriptors and match algorithms).
-
Used 'struct' to keep track of experiments - Config2DFeatTrack and AuditLog
//struct to hold experiment configuration struct Config2DFeatTrack { std::string detectorType = "SHITOMASI"; std::string descriptorType = "BRISK"; // BRIEF, ORB, FREAK, AKAZE, SIFT std::string matcherType = "MAT_BF"; // MAT_BF, MAT_FLANN std::string matcherTypeMetric = "DES_BINARY"; // DES_BINARY, DES_HOG std::string matcherTypeSelector = "SEL_NN"; // SEL_NN, SEL_KNN bool bVis = false; bool bLimitKpts = false; int maxKeypoints = 50; }; //struct to hold experiment audit log struct AuditLog { Config2DFeatTrack config ; std::string image_name =""; bool isError = false; long match_time = 0; long match_keypoints_size = 0; long match_removed_keypoints_size = 0; long desc_time = 0; long detect_time = 0; long detect_keypoints_size = 0; };
-
Now dyanamically create a new array of Config2DFeatTrack with all possible combinations from following setting.
vector<Config2DFeatTrack> configList; vector<string> detectorTypes = {"SHITOMASI", "HARRIS", "FAST", "BRISK", "ORB", "AKAZE", "SIFT"}; vector<string> descriptorTypes = {"BRISK", "BRIEF", "ORB", "FREAK", "AKAZE", "SIFT"}; vector<string> matcherTypes = {"MAT_BF", "MAT_FLANN"}; vector<string> matcherTypeMetrics = {"DES_BINARY", "DES_HOG"}; vector<string> matcherTypeSelectors = {"SEL_NN", "SEL_KNN"}; ... ... for (auto matcherType:matcherTypes) { for (auto matcherTypeMetric:matcherTypeMetrics) { for (auto matcherTypeSelector:matcherTypeSelectors) { Config2DFeatTrack config; config.detectorType = detectorType; config.descriptorType = descriptorType; config.matcherType = matcherType; config.matcherTypeMetric = matcherTypeMetric; config.matcherTypeSelector = matcherTypeSelector; configList.push_back(config); } } } ... ...
-
To run all combinations of algorithms or one set of algorithm. Please change 'singleTest' in 'MidTermProject_Camera_Student.cpp -> main'
//'MidTermProject_Camera_Student.cpp -> main' // for testing one set of algorithms use singleTest = true //if singleTest = false, will run all combinations of algorithms bool singleTest = false; vector<Config2DFeatTrack> configList = getConfig(singleTest); ```
-
output of log outputed into three files runtest.log
results.csv
error,image_name,detectorType,descriptorType,matcherType,matcherTypeMetric,matcherTypeSelector,detect_time,desc_time,match_time,detect_keypoints_size,match_keypoints_size,match_removed_keypoints_size,bVis,bLimitKpts,maxKeypoints 0,../images/KITTI/2011_09_26/image_00/data/0000000000.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,19,345,0,1370,0,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000001.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,19,346,0,1301,125,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000002.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,19,339,0,1361,118,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000003.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,16,338,0,1358,123,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000004.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,16,336,0,1333,120,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000005.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,17,338,0,1284,120,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000006.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,17,336,0,1322,113,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000007.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,16,337,0,1366,114,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000008.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,17,336,0,1389,123,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000009.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_NN,17,337,0,1339,111,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000000.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_KNN,16,336,0,1370,0,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000001.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_KNN,17,334,0,1301,95,30,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000002.png,SHITOMASI,BRISK,MAT_BF,DES_BINARY,SEL_KNN,17,334,0,1361,88,30,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000007.png,SHITOMASI,SIFT,MAT_FLANN,DES_BINARY,SEL_KNN,11,17,3,1366,96,18,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000008.png,SHITOMASI,SIFT,MAT_FLANN,DES_BINARY,SEL_KNN,11,19,2,1389,106,17,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000009.png,SHITOMASI,SIFT,MAT_FLANN,DES_BINARY,SEL_KNN,17,15,2,1339,97,14,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000000.png,SHITOMASI,SIFT,MAT_FLANN,DES_HOG,SEL_NN,11,19,0,1370,0,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000001.png,SHITOMASI,SIFT,MAT_FLANN,DES_HOG,SEL_NN,11,16,2,1301,125,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000002.png,SHITOMASI,SIFT,MAT_FLANN,DES_HOG,SEL_NN,11,15,2,1361,118,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000003.png,SHITOMASI,SIFT,MAT_FLANN,DES_HOG,SEL_NN,16,15,2,1358,123,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000004.png,SHITOMASI,SIFT,MAT_FLANN,DES_HOG,SEL_NN,11,15,2,1333,120,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000005.png,SHITOMASI,SIFT,MAT_FLANN,DES_HOG,SEL_NN,12,16,2,1284,120,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000006.png,SHITOMASI,SIFT,MAT_FLANN,DES_HOG,SEL_NN,11,15,1,1322,113,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000000.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,327,0,1824,0,0,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000001.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,328,0,1832,97,52,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000002.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,329,0,1810,104,48,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000003.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,334,0,1817,101,49,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000004.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,328,0,1793,98,57,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000005.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,332,0,1796,85,64,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000006.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,329,0,1788,107,42,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000007.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,327,0,1695,107,49,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000008.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,325,0,1749,100,50,0,0,50 0,../images/KITTI/2011_09_26/image_00/data/0000000009.png,FAST,BRISK,MAT_BF,DES_BINARY,SEL_KNN,1,326,0,1770,100,38,0,0,50
results.json
[ { 'isError': '0', 'image_name': '../images/KITTI/2011_09_26/image_00/data/0000000000.png', 'detectorType': 'SHITOMASI', 'descriptorType': 'BRISK', 'matcherType': 'MAT_BF', 'matcherTypeMetric': 'DES_BINARY', 'matcherTypeSelector': 'SEL_NN', 'detect_time_ms': 19, 'desc_time_ms': 339, 'match_time_ms': 0, 'detect_keypoints_size': 1370, 'match_keypoints_size': 0, 'match_removed_keypoints_size': 0, 'bVis': 0, 'bLimitKpts': 0, 'maxKeypoints': 50, }, { 'isError': '0', 'image_name': '../images/KITTI/2011_09_26/image_00/data/0000000001.png', 'detectorType': 'SHITOMASI', 'descriptorType': 'BRISK', 'matcherType': 'MAT_BF', 'matcherTypeMetric': 'DES_BINARY', 'matcherTypeSelector': 'SEL_NN', 'detect_time_ms': 17, 'desc_time_ms': 343, 'match_time_ms': 0, 'detect_keypoints_size': 1301, 'match_keypoints_size': 125, 'match_removed_keypoints_size': 0, 'bVis': 0, 'bLimitKpts': 0, 'maxKeypoints': 50, }, { 'isError': '0', 'image_name': '../images/KITTI/2011_09_26/image_00/data/0000000002.png', 'detectorType': 'SHITOMASI', 'descriptorType': 'BRISK', 'matcherType': 'MAT_BF', 'matcherTypeMetric': 'DES_BINARY', 'matcherTypeSelector': 'SEL_NN', 'detect_time_ms': 17, 'desc_time_ms': 337, 'match_time_ms': 0, 'detect_keypoints_size': 1361, 'match_keypoints_size': 118, 'match_removed_keypoints_size': 0, 'bVis': 0, 'bLimitKpts': 0, 'maxKeypoints': 50, }, { 'isError': '0', 'image_name': '../images/KITTI/2011_09_26/image_00/data/0000000003.png', 'detectorType': 'SHITOMASI', 'descriptorType': 'BRISK', 'matcherType': 'MAT_BF', 'matcherTypeMetric': 'DES_BINARY', 'matcherTypeSelector': 'SEL_NN', 'detect_time_ms': 17, 'desc_time_ms': 341, 'match_time_ms': 0, 'detect_keypoints_size': 1358, 'match_keypoints_size': 123, 'match_removed_keypoints_size': 0, 'bVis': 0, 'bLimitKpts': 0, 'maxKeypoints': 50, }, { 'isError': '0', 'image_name': '../images/KITTI/2011_09_26/image_00/data/0000000004.png', 'detectorType': 'SHITOMASI', 'descriptorType': 'BRISK', 'matcherType': 'MAT_BF', 'matcherTypeMetric': 'DES_BINARY', 'matcherTypeSelector': 'SEL_NN', 'detect_time_ms': 16, 'desc_time_ms': 336, 'match_time_ms': 0, 'detect_keypoints_size': 1333, 'match_keypoints_size': 120, 'match_removed_keypoints_size': 0, 'bVis': 0, 'bLimitKpts': 0, 'maxKeypoints': 50, }, { 'isError': '0', 'image_name': '../images/KITTI/2011_09_26/image_00/data/0000000005.png', 'detectorType': 'SHITOMASI', 'descriptorType': 'BRISK', 'matcherType': 'MAT_BF', 'matcherTypeMetric': 'DES_BINARY', 'matcherTypeSelector': 'SEL_NN', 'detect_time_ms': 18, 'desc_time_ms': 341, 'match_time_ms': 0, 'detect_keypoints_size': 1284, 'match_keypoints_size': 120, 'match_removed_keypoints_size': 0, 'bVis': 0, 'bLimitKpts': 0, 'maxKeypoints': 50, }, { 'isError': '0', 'image_name': '../images/KITTI/2011_09_26/image_00/data/0000000006.png', 'detectorType': 'SHITOMASI', 'descriptorType': 'BRISK', 'matcherType': 'MAT_BF', 'matcherTypeMetric': 'DES_BINARY', 'matcherTypeSelector': 'SEL_NN', 'detect_time_ms': 16, 'desc_time_ms': 342, 'match_time_ms': 0, 'detect_keypoints_size': 1322, 'match_keypoints_size': 113, 'match_removed_keypoints_size': 0, 'bVis': 0, 'bLimitKpts': 0, 'maxKeypoints': 50, }, { 'isError': '0', 'image_name': '../images/KITTI/2011_09_26/image_00/data/0000000007.png', 'detectorType': 'SHITOMASI', 'descriptorType': 'BRISK', 'matcherType': 'MAT_BF', 'matcherTypeMetric': 'DES_BINARY', 'matcherTypeSelector': 'SEL_NN', 'detect_time_ms': 16, 'desc_time_ms': 339, 'match_time_ms': 0, 'detect_keypoints_size': 1366, 'match_keypoints_size': 114, 'match_removed_keypoints_size': 0, 'bVis': 0, 'bLimitKpts': 0, 'maxKeypoints': 50, }, { 'isError': '0', 'image_name': '../images/KITTI/2011_09_26/image_00/data/0000000008.png', 'detectorType': 'SHITOMASI', 'descriptorType': 'BRISK', 'matcherType': 'MAT_BF', 'matcherTypeMetric': 'DES_BINARY', 'matcherTypeSelector': 'SEL_NN', 'detect_time_ms': 17, 'desc_time_ms': 339, 'match_time_ms': 0, 'detect_keypoints_size': 1389, 'match_keypoints_size': 123, 'match_removed_keypoints_size': 0, 'bVis': 0, 'bLimitKpts': 0, 'maxKeypoints': 50, }, ]
import pandas as pd
import numpy as np
import os.path
def get_image_name(path):
return os.path.basename(path)
df = pd.read_csv("results.csv")
df['image_name'] = df['image_name'].apply(get_image_name)
del df['error']
df.head(3)
image_name | detectorType | descriptorType | matcherType | matcherTypeMetric | matcherTypeSelector | detect_time | desc_time | match_time | detect_keypoints_size | match_keypoints_size | match_removed_keypoints_size | bVis | bLimitKpts | maxKeypoints | |
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
0 | 0000000000.png | SHITOMASI | BRISK | MAT_BF | DES_BINARY | SEL_NN | 19 | 339 | 0 | 1370 | 0 | 0 | 0 | 0 | 50 |
1 | 0000000001.png | SHITOMASI | BRISK | MAT_BF | DES_BINARY | SEL_NN | 17 | 343 | 0 | 1301 | 125 | 0 | 0 | 0 | 50 |
2 | 0000000002.png | SHITOMASI | BRISK | MAT_BF | DES_BINARY | SEL_NN | 17 | 337 | 0 | 1361 | 118 | 0 | 0 | 0 | 50 |
detect_time by detectorType
df_detect= df.groupby(['detectorType']).mean()
df_detect.sort_values(by=['detect_time'], ascending=[1])
detect_time | desc_time | match_time | detect_keypoints_size | match_keypoints_size | match_removed_keypoints_size | bVis | bLimitKpts | maxKeypoints | |
---|---|---|---|---|---|---|---|---|---|
detectorType | |||||||||
FAST | 0.933333 | 65.425000 | 0.739583 | 1787.4 | 84.781250 | 16.318750 | 0.0 | 0.0 | 50.0 |
ORB | 7.445833 | 69.620833 | 0.427083 | 500.0 | 55.825000 | 12.200000 | 0.0 | 0.0 | 50.0 |
SHITOMASI | 14.931250 | 65.900000 | 0.543750 | 1342.3 | 69.845833 | 10.179167 | 0.0 | 0.0 | 50.0 |
HARRIS | 16.062500 | 64.222917 | 0.000000 | 173.7 | 13.500000 | 2.550000 | 0.0 | 0.0 | 50.0 |
AKAZE | 72.608333 | 75.564583 | 0.972917 | 1342.9 | 121.081250 | 15.593750 | 0.0 | 0.0 | 50.0 |
SIFT | 124.356250 | 71.014583 | 0.531250 | 1386.2 | 54.454167 | 18.220833 | 0.0 | 0.0 | 50.0 |
BRISK | 365.677083 | 68.922917 | 1.629167 | 2711.6 | 145.668750 | 39.397917 | 0.0 | 0.0 | 50.0 |
detect_time by descriptorType
df_detect2= df.groupby(['descriptorType']).mean()
df_detect2.sort_values(by=['detect_time'], ascending=[1])
detect_time | desc_time | match_time | detect_keypoints_size | match_keypoints_size | match_removed_keypoints_size | bVis | bLimitKpts | maxKeypoints | |
---|---|---|---|---|---|---|---|---|---|
descriptorType | |||||||||
SIFT | 82.450000 | 35.317857 | 1.037500 | 1320.585714 | 55.564286 | 8.078571 | 0.0 | 0.0 | 50.0 |
FREAK | 85.591071 | 40.201786 | 0.776786 | 1320.585714 | 93.953571 | 23.675000 | 0.0 | 0.0 | 50.0 |
BRISK | 86.833929 | 325.205357 | 0.864286 | 1320.585714 | 102.894643 | 23.191071 | 0.0 | 0.0 | 50.0 |
AKAZE | 86.875000 | 8.635714 | 0.128571 | 1320.585714 | 19.337500 | 1.962500 | 0.0 | 0.0 | 50.0 |
BRIEF | 86.998214 | 0.608929 | 0.667857 | 1320.585714 | 105.757143 | 21.528571 | 0.0 | 0.0 | 50.0 |
ORB | 87.264286 | 2.033929 | 0.676786 | 1320.585714 | 89.769643 | 19.673214 | 0.0 | 0.0 | 50.0 |
desc_time by detectorType
df_detect= df.groupby(['detectorType']).mean()
df_detect.sort_values(by=['desc_time'], ascending=[1])
detect_time | desc_time | match_time | detect_keypoints_size | match_keypoints_size | match_removed_keypoints_size | bVis | bLimitKpts | maxKeypoints | |
---|---|---|---|---|---|---|---|---|---|
detectorType | |||||||||
HARRIS | 16.062500 | 64.222917 | 0.000000 | 173.7 | 13.500000 | 2.550000 | 0.0 | 0.0 | 50.0 |
FAST | 0.933333 | 65.425000 | 0.739583 | 1787.4 | 84.781250 | 16.318750 | 0.0 | 0.0 | 50.0 |
SHITOMASI | 14.931250 | 65.900000 | 0.543750 | 1342.3 | 69.845833 | 10.179167 | 0.0 | 0.0 | 50.0 |
BRISK | 365.677083 | 68.922917 | 1.629167 | 2711.6 | 145.668750 | 39.397917 | 0.0 | 0.0 | 50.0 |
ORB | 7.445833 | 69.620833 | 0.427083 | 500.0 | 55.825000 | 12.200000 | 0.0 | 0.0 | 50.0 |
SIFT | 124.356250 | 71.014583 | 0.531250 | 1386.2 | 54.454167 | 18.220833 | 0.0 | 0.0 | 50.0 |
AKAZE | 72.608333 | 75.564583 | 0.972917 | 1342.9 | 121.081250 | 15.593750 | 0.0 | 0.0 | 50.0 |
desc_time by descriptorType
df_detect= df.groupby(['descriptorType']).mean()
df_detect.sort_values(by=['desc_time'], ascending=[1])
detect_time | desc_time | match_time | detect_keypoints_size | match_keypoints_size | match_removed_keypoints_size | bVis | bLimitKpts | maxKeypoints | |
---|---|---|---|---|---|---|---|---|---|
descriptorType | |||||||||
BRIEF | 86.998214 | 0.608929 | 0.667857 | 1320.585714 | 105.757143 | 21.528571 | 0.0 | 0.0 | 50.0 |
ORB | 87.264286 | 2.033929 | 0.676786 | 1320.585714 | 89.769643 | 19.673214 | 0.0 | 0.0 | 50.0 |
AKAZE | 86.875000 | 8.635714 | 0.128571 | 1320.585714 | 19.337500 | 1.962500 | 0.0 | 0.0 | 50.0 |
SIFT | 82.450000 | 35.317857 | 1.037500 | 1320.585714 | 55.564286 | 8.078571 | 0.0 | 0.0 | 50.0 |
FREAK | 85.591071 | 40.201786 | 0.776786 | 1320.585714 | 93.953571 | 23.675000 | 0.0 | 0.0 | 50.0 |
BRISK | 86.833929 | 325.205357 | 0.864286 | 1320.585714 | 102.894643 | 23.191071 | 0.0 | 0.0 | 50.0 |
detect_time by descriptorType, detectorType
df_detect3= df.groupby(['descriptorType', 'detectorType']).mean()
df_detect3.sort_values(by=['detect_time'], ascending=[0])
detect_time | desc_time | match_time | detect_keypoints_size | match_keypoints_size | match_removed_keypoints_size | bVis | bLimitKpts | maxKeypoints | ||
---|---|---|---|---|---|---|---|---|---|---|
descriptorType | detectorType | |||||||||
ORB | BRISK | 369.7000 | 4.0750 | 1.8500 | 2711.6 | 187.4500 | 63.3500 | 0.0 | 0.0 | 50.0 |
BRIEF | BRISK | 367.4750 | 1.0125 | 1.6750 | 2711.6 | 202.2250 | 48.5750 | 0.0 | 0.0 | 50.0 |
BRISK | BRISK | 366.1625 | 327.3625 | 2.1500 | 2711.6 | 197.6250 | 53.1750 | 0.0 | 0.0 | 50.0 |
AKAZE | BRISK | 364.1625 | 0.0000 | 0.0000 | 2711.6 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
FREAK | BRISK | 363.5875 | 40.2000 | 1.8875 | 2711.6 | 182.4250 | 50.1750 | 0.0 | 0.0 | 50.0 |
SIFT | BRISK | 362.9750 | 40.8875 | 2.2125 | 2711.6 | 104.2875 | 21.1125 | 0.0 | 0.0 | 50.0 |
ORB | SIFT | 128.9125 | 0.0000 | 0.0000 | 1386.2 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
FREAK | SIFT | 128.7250 | 39.4625 | 0.7875 | 1386.2 | 89.5625 | 34.3375 | 0.0 | 0.0 | 50.0 |
AKAZE | SIFT | 127.7625 | 0.0000 | 0.0000 | 1386.2 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
BRIEF | SIFT | 127.7500 | 0.5500 | 0.5750 | 1386.2 | 95.1125 | 29.7875 | 0.0 | 0.0 | 50.0 |
BRISK | SIFT | 127.0875 | 305.2000 | 0.8750 | 1386.2 | 90.7375 | 34.0625 | 0.0 | 0.0 | 50.0 |
SIFT | SIFT | 105.9000 | 80.8750 | 0.9500 | 1386.2 | 51.3125 | 11.1375 | 0.0 | 0.0 | 50.0 |
BRISK | AKAZE | 73.9875 | 325.3750 | 0.9500 | 1342.9 | 132.8250 | 16.2750 | 0.0 | 0.0 | 50.0 |
AKAZE | AKAZE | 73.3750 | 60.4500 | 0.9000 | 1342.9 | 135.3625 | 13.7375 | 0.0 | 0.0 | 50.0 |
ORB | AKAZE | 73.0750 | 3.1875 | 0.9625 | 1342.9 | 127.0250 | 22.0750 | 0.0 | 0.0 | 50.0 |
BRIEF | AKAZE | 72.7750 | 0.9500 | 0.8000 | 1342.9 | 133.4750 | 15.6250 | 0.0 | 0.0 | 50.0 |
FREAK | AKAZE | 72.2250 | 39.6500 | 0.9250 | 1342.9 | 128.5750 | 20.5250 | 0.0 | 0.0 | 50.0 |
SIFT | AKAZE | 70.2125 | 23.7750 | 1.3000 | 1342.9 | 69.2250 | 5.3250 | 0.0 | 0.0 | 50.0 |
AKAZE | HARRIS | 17.8000 | 0.0000 | 0.0000 | 173.7 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
BRISK | SHITOMASI | 16.9000 | 336.1125 | 0.6625 | 1342.3 | 89.7375 | 16.9625 | 0.0 | 0.0 | 50.0 |
SIFT | HARRIS | 16.7500 | 15.7500 | 0.0000 | 173.7 | 9.4250 | 1.2750 | 0.0 | 0.0 | 50.0 |
BRIEF | HARRIS | 16.7000 | 0.0750 | 0.0000 | 173.7 | 18.5500 | 2.8500 | 0.0 | 0.0 | 50.0 |
SHITOMASI | 16.2125 | 1.0125 | 0.5000 | 1342.3 | 97.3000 | 9.4000 | 0.0 | 0.0 | 50.0 | |
ORB | SHITOMASI | 16.1375 | 1.0000 | 0.5750 | 1342.3 | 95.2750 | 11.4250 | 0.0 | 0.0 | 50.0 |
AKAZE | SHITOMASI | 15.8750 | 0.0000 | 0.0000 | 1342.3 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
BRISK | HARRIS | 15.4750 | 327.7625 | 0.0000 | 173.7 | 17.2750 | 4.1250 | 0.0 | 0.0 | 50.0 |
ORB | HARRIS | 15.0125 | 0.6500 | 0.0000 | 173.7 | 18.3750 | 3.0250 | 0.0 | 0.0 | 50.0 |
FREAK | HARRIS | 14.6375 | 41.1000 | 0.0000 | 173.7 | 17.3750 | 4.0250 | 0.0 | 0.0 | 50.0 |
SIFT | SHITOMASI | 12.7250 | 16.0125 | 0.9125 | 1342.3 | 49.8500 | 3.5000 | 0.0 | 0.0 | 50.0 |
FREAK | SHITOMASI | 11.7375 | 41.2625 | 0.6125 | 1342.3 | 86.9125 | 19.7875 | 0.0 | 0.0 | 50.0 |
AKAZE | ORB | 8.1750 | 0.0000 | 0.0000 | 500.0 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
SIFT | ORB | 7.5875 | 47.6750 | 0.7375 | 500.0 | 44.9750 | 6.6750 | 0.0 | 0.0 | 50.0 |
FREAK | ORB | 7.2625 | 39.0625 | 0.3250 | 500.0 | 46.6250 | 8.2750 | 0.0 | 0.0 | 50.0 |
BRIEF | ORB | 7.2375 | 0.1875 | 0.4500 | 500.0 | 76.5625 | 26.7375 | 0.0 | 0.0 | 50.0 |
BRISK | ORB | 7.2250 | 326.4750 | 0.5125 | 500.0 | 82.5750 | 12.4250 | 0.0 | 0.0 | 50.0 |
ORB | ORB | 7.1875 | 4.3250 | 0.5375 | 500.0 | 84.2125 | 19.0875 | 0.0 | 0.0 | 50.0 |
BRISK | FAST | 1.0000 | 328.1500 | 0.9000 | 1787.4 | 109.4875 | 25.3125 | 0.0 | 0.0 | 50.0 |
SIFT | FAST | 1.0000 | 22.2500 | 1.1500 | 1787.4 | 59.8750 | 7.5250 | 0.0 | 0.0 | 50.0 |
AKAZE | FAST | 0.9750 | 0.0000 | 0.0000 | 1787.4 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
FREAK | FAST | 0.9625 | 40.6750 | 0.9000 | 1787.4 | 106.2000 | 28.6000 | 0.0 | 0.0 | 50.0 |
BRIEF | FAST | 0.8375 | 0.4750 | 0.6750 | 1787.4 | 117.0750 | 17.7250 | 0.0 | 0.0 | 50.0 |
ORB | FAST | 0.8250 | 1.0000 | 0.8125 | 1787.4 | 116.0500 | 18.7500 | 0.0 | 0.0 | 50.0 |
desc_time by descriptorType, detectorType
df_detect3= df.groupby(['descriptorType', 'detectorType']).mean()
df_detect3.sort_values(by=['desc_time'], ascending=[0])
detect_time | desc_time | match_time | detect_keypoints_size | match_keypoints_size | match_removed_keypoints_size | bVis | bLimitKpts | maxKeypoints | ||
---|---|---|---|---|---|---|---|---|---|---|
descriptorType | detectorType | |||||||||
BRISK | SHITOMASI | 16.9000 | 336.1125 | 0.6625 | 1342.3 | 89.7375 | 16.9625 | 0.0 | 0.0 | 50.0 |
FAST | 1.0000 | 328.1500 | 0.9000 | 1787.4 | 109.4875 | 25.3125 | 0.0 | 0.0 | 50.0 | |
HARRIS | 15.4750 | 327.7625 | 0.0000 | 173.7 | 17.2750 | 4.1250 | 0.0 | 0.0 | 50.0 | |
BRISK | 366.1625 | 327.3625 | 2.1500 | 2711.6 | 197.6250 | 53.1750 | 0.0 | 0.0 | 50.0 | |
ORB | 7.2250 | 326.4750 | 0.5125 | 500.0 | 82.5750 | 12.4250 | 0.0 | 0.0 | 50.0 | |
AKAZE | 73.9875 | 325.3750 | 0.9500 | 1342.9 | 132.8250 | 16.2750 | 0.0 | 0.0 | 50.0 | |
SIFT | 127.0875 | 305.2000 | 0.8750 | 1386.2 | 90.7375 | 34.0625 | 0.0 | 0.0 | 50.0 | |
SIFT | SIFT | 105.9000 | 80.8750 | 0.9500 | 1386.2 | 51.3125 | 11.1375 | 0.0 | 0.0 | 50.0 |
AKAZE | AKAZE | 73.3750 | 60.4500 | 0.9000 | 1342.9 | 135.3625 | 13.7375 | 0.0 | 0.0 | 50.0 |
SIFT | ORB | 7.5875 | 47.6750 | 0.7375 | 500.0 | 44.9750 | 6.6750 | 0.0 | 0.0 | 50.0 |
FREAK | SHITOMASI | 11.7375 | 41.2625 | 0.6125 | 1342.3 | 86.9125 | 19.7875 | 0.0 | 0.0 | 50.0 |
HARRIS | 14.6375 | 41.1000 | 0.0000 | 173.7 | 17.3750 | 4.0250 | 0.0 | 0.0 | 50.0 | |
SIFT | BRISK | 362.9750 | 40.8875 | 2.2125 | 2711.6 | 104.2875 | 21.1125 | 0.0 | 0.0 | 50.0 |
FREAK | FAST | 0.9625 | 40.6750 | 0.9000 | 1787.4 | 106.2000 | 28.6000 | 0.0 | 0.0 | 50.0 |
BRISK | 363.5875 | 40.2000 | 1.8875 | 2711.6 | 182.4250 | 50.1750 | 0.0 | 0.0 | 50.0 | |
AKAZE | 72.2250 | 39.6500 | 0.9250 | 1342.9 | 128.5750 | 20.5250 | 0.0 | 0.0 | 50.0 | |
SIFT | 128.7250 | 39.4625 | 0.7875 | 1386.2 | 89.5625 | 34.3375 | 0.0 | 0.0 | 50.0 | |
ORB | 7.2625 | 39.0625 | 0.3250 | 500.0 | 46.6250 | 8.2750 | 0.0 | 0.0 | 50.0 | |
SIFT | AKAZE | 70.2125 | 23.7750 | 1.3000 | 1342.9 | 69.2250 | 5.3250 | 0.0 | 0.0 | 50.0 |
FAST | 1.0000 | 22.2500 | 1.1500 | 1787.4 | 59.8750 | 7.5250 | 0.0 | 0.0 | 50.0 | |
SHITOMASI | 12.7250 | 16.0125 | 0.9125 | 1342.3 | 49.8500 | 3.5000 | 0.0 | 0.0 | 50.0 | |
HARRIS | 16.7500 | 15.7500 | 0.0000 | 173.7 | 9.4250 | 1.2750 | 0.0 | 0.0 | 50.0 | |
ORB | ORB | 7.1875 | 4.3250 | 0.5375 | 500.0 | 84.2125 | 19.0875 | 0.0 | 0.0 | 50.0 |
BRISK | 369.7000 | 4.0750 | 1.8500 | 2711.6 | 187.4500 | 63.3500 | 0.0 | 0.0 | 50.0 | |
AKAZE | 73.0750 | 3.1875 | 0.9625 | 1342.9 | 127.0250 | 22.0750 | 0.0 | 0.0 | 50.0 | |
BRIEF | SHITOMASI | 16.2125 | 1.0125 | 0.5000 | 1342.3 | 97.3000 | 9.4000 | 0.0 | 0.0 | 50.0 |
BRISK | 367.4750 | 1.0125 | 1.6750 | 2711.6 | 202.2250 | 48.5750 | 0.0 | 0.0 | 50.0 | |
ORB | FAST | 0.8250 | 1.0000 | 0.8125 | 1787.4 | 116.0500 | 18.7500 | 0.0 | 0.0 | 50.0 |
SHITOMASI | 16.1375 | 1.0000 | 0.5750 | 1342.3 | 95.2750 | 11.4250 | 0.0 | 0.0 | 50.0 | |
BRIEF | AKAZE | 72.7750 | 0.9500 | 0.8000 | 1342.9 | 133.4750 | 15.6250 | 0.0 | 0.0 | 50.0 |
ORB | HARRIS | 15.0125 | 0.6500 | 0.0000 | 173.7 | 18.3750 | 3.0250 | 0.0 | 0.0 | 50.0 |
BRIEF | SIFT | 127.7500 | 0.5500 | 0.5750 | 1386.2 | 95.1125 | 29.7875 | 0.0 | 0.0 | 50.0 |
FAST | 0.8375 | 0.4750 | 0.6750 | 1787.4 | 117.0750 | 17.7250 | 0.0 | 0.0 | 50.0 | |
ORB | 7.2375 | 0.1875 | 0.4500 | 500.0 | 76.5625 | 26.7375 | 0.0 | 0.0 | 50.0 | |
HARRIS | 16.7000 | 0.0750 | 0.0000 | 173.7 | 18.5500 | 2.8500 | 0.0 | 0.0 | 50.0 | |
AKAZE | HARRIS | 17.8000 | 0.0000 | 0.0000 | 173.7 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
ORB | SIFT | 128.9125 | 0.0000 | 0.0000 | 1386.2 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
AKAZE | SIFT | 127.7625 | 0.0000 | 0.0000 | 1386.2 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |
SHITOMASI | 15.8750 | 0.0000 | 0.0000 | 1342.3 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 | |
BRISK | 364.1625 | 0.0000 | 0.0000 | 2711.6 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 | |
FAST | 0.9750 | 0.0000 | 0.0000 | 1787.4 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 | |
ORB | 8.1750 | 0.0000 | 0.0000 | 500.0 | 0.0000 | 0.0000 | 0.0 | 0.0 | 50.0 |