├── CMakeLists.txt
├── README.md
├── bin
├── 1.jpg
├── ORBextractor
└── orb_features.jpg
├── include
└── ORBextractor.h
├── lib
└── liborbextractor.so
├── param
└── orb.yaml
├── screenshots
├── 1.jpg
├── 2.jpg
├── liu1.jpg
└── liu2.jpg
└── src
├── ORBextractor
├── ORBextractor.cpp
└── main.cpp
/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8)
2 | project(orbextractor)
3 |
4 | IF(NOT CMAKE_BUILD_TYPE)
5 | SET(CMAKE_BUILD_TYPE Release)
6 | ENDIF()
7 |
8 | MESSAGE("Build type: " ${CMAKE_BUILD_TYPE})
9 |
10 | set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ")
11 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native")
12 |
13 | # Check C++11 or C++0x support
14 | include(CheckCXXCompilerFlag)
15 | CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11)
16 | CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X)
17 | if(COMPILER_SUPPORTS_CXX11)
18 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
19 | add_definitions(-DCOMPILEDWITHC11)
20 | message(STATUS "Using flag -std=c++11.")
21 | elseif(COMPILER_SUPPORTS_CXX0X)
22 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x")
23 | add_definitions(-DCOMPILEDWITHC0X)
24 | message(STATUS "Using flag -std=c++0x.")
25 | else()
26 | message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.")
27 | endif()
28 |
29 | #LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
30 |
31 | find_package(OpenCV 3.0 QUIET)
32 | if(NOT OpenCV_FOUND)
33 | find_package(OpenCV 2.4.3 QUIET)
34 | if(NOT OpenCV_FOUND)
35 | message(FATAL_ERROR "OpenCV > 2.4.3 not found.")
36 | endif()
37 | endif()
38 |
39 |
40 | include_directories(
41 | ${PROJECT_SOURCE_DIR}
42 | ${PROJECT_SOURCE_DIR}/include
43 | )
44 |
45 | set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/lib)
46 |
47 | add_library(${PROJECT_NAME} SHARED
48 | src/ORBextractor.cpp
49 | )
50 |
51 | target_link_libraries(${PROJECT_NAME}
52 | ${OpenCV_LIBS}
53 | )
54 |
55 | # Build examples
56 |
57 | set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/bin)
58 |
59 | add_executable(ORBextractor
60 | src/main.cpp)
61 | target_link_libraries(ORBextractor ${PROJECT_NAME})
62 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # orb-extractor
2 |
3 | **29 Nov 2019**
4 |
5 | I separate orb-feature extractor code from [orbslam2 project](https://github.com/raulmur/ORB_SLAM2).
6 |
7 | # 1. Prerequisites
8 | I have tested the library in **Ubuntu 18.04**
9 |
10 | ## C++11 or C++0x Compiler
11 |
12 | ## OpenCV
13 | I use [OpenCV](http://opencv.org) to manipulate images and features.My version is 3.4.8.
14 |
15 | # 2. Building this library and examples(main.cpp)
16 |
17 | Clone the repository:
18 | ```
19 | git clone https://github.com/slaming/ORBExtractor
20 | ```
21 | ```
22 | cd ORBExtractor
23 | ```
24 | ```
25 | mkdir build
26 | ```
27 | ```
28 | cd build
29 | ```
30 | ```
31 | cmake ..
32 | ```
33 | ```
34 | build -j4
35 | ```
36 |
37 | # 3.Examples(main.cpp)
38 |
39 | ```
40 | cd bin
41 | ```
42 | ```
43 | ./ORBextractor ../pictures/liu2.jpg ../param/orb.yaml
44 | ```
45 |
46 | ## Provide two results
47 | ### First
48 |
50 |
52 | ### Second
53 |
55 |
57 |
--------------------------------------------------------------------------------
/bin/1.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/liuzhenboo/orb-extractor/538dbab86a60fd6632b4d222819fe2058332fcc2/bin/1.jpg
--------------------------------------------------------------------------------
/bin/ORBextractor:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/liuzhenboo/orb-extractor/538dbab86a60fd6632b4d222819fe2058332fcc2/bin/ORBextractor
--------------------------------------------------------------------------------
/bin/orb_features.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/liuzhenboo/orb-extractor/538dbab86a60fd6632b4d222819fe2058332fcc2/bin/orb_features.jpg
--------------------------------------------------------------------------------
/include/ORBextractor.h:
--------------------------------------------------------------------------------
1 | #ifndef ORBEXTRACTOR_H
2 | #define ORBEXTRACTOR_H
3 |
4 | #include
5 | #include
6 | #include
7 |
8 |
9 | namespace ORB_SLAM2
10 | {
11 |
12 | class ExtractorNode
13 | {
14 | public:
15 | ExtractorNode():bNoMore(false){}
16 |
17 | void DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4);
18 |
19 | std::vector vKeys;
20 | cv::Point2i UL, UR, BL, BR;
21 | std::list::iterator lit;
22 | bool bNoMore;
23 | };
24 |
25 | class ORBextractor
26 | {
27 | public:
28 |
29 | enum {HARRIS_SCORE=0, FAST_SCORE=1 };
30 |
31 | ORBextractor(int nfeatures, float scaleFactor, int nlevels,
32 | int iniThFAST, int minThFAST);
33 |
34 | ~ORBextractor(){}
35 |
36 | // Compute the ORB features and descriptors on an image.
37 | // ORB are dispersed on the image using an octree.
38 | // Mask is ignored in the current implementation.
39 | void operator()( cv::InputArray image, cv::InputArray mask,
40 | std::vector& keypoints,
41 | cv::OutputArray descriptors);
42 |
43 | int inline GetLevels(){
44 | return nlevels;}
45 |
46 | float inline GetScaleFactor(){
47 | return scaleFactor;}
48 |
49 | std::vector inline GetScaleFactors(){
50 | return mvScaleFactor;
51 | }
52 |
53 | std::vector inline GetInverseScaleFactors(){
54 | return mvInvScaleFactor;
55 | }
56 |
57 | std::vector inline GetScaleSigmaSquares(){
58 | return mvLevelSigma2;
59 | }
60 |
61 | std::vector inline GetInverseScaleSigmaSquares(){
62 | return mvInvLevelSigma2;
63 | }
64 |
65 | std::vector mvImagePyramid;
66 |
67 | protected:
68 |
69 | void ComputePyramid(cv::Mat image);
70 | void ComputeKeyPointsOctTree(std::vector >& allKeypoints);
71 | std::vector DistributeOctTree(const std::vector& vToDistributeKeys, const int &minX,
72 | const int &maxX, const int &minY, const int &maxY, const int &nFeatures, const int &level);
73 |
74 | void ComputeKeyPointsOld(std::vector >& allKeypoints);
75 | std::vector pattern;
76 |
77 | int nfeatures;
78 | double scaleFactor;
79 | int nlevels;
80 | int iniThFAST;
81 | int minThFAST;
82 |
83 | std::vector mnFeaturesPerLevel;
84 |
85 | std::vector umax;
86 |
87 | std::vector mvScaleFactor;
88 | std::vector mvInvScaleFactor;
89 | std::vector mvLevelSigma2;
90 | std::vector mvInvLevelSigma2;
91 | };
92 |
93 | } //namespace ORB_SLAM
94 |
95 | #endif
96 |
97 |
--------------------------------------------------------------------------------
/lib/liborbextractor.so:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/liuzhenboo/orb-extractor/538dbab86a60fd6632b4d222819fe2058332fcc2/lib/liborbextractor.so
--------------------------------------------------------------------------------
/param/orb.yaml:
--------------------------------------------------------------------------------
1 | %YAML:1.0
2 |
3 | #--------------------------------------------------------------------------------------------
4 | # ORB Parameters
5 | #--------------------------------------------------------------------------------------------
6 |
7 | # ORB Extractor: Number of features per image
8 | ORBextractor.nFeatures: 2000
9 |
10 | # ORB Extractor: Scale factor between levels in the scale pyramid
11 | ORBextractor.scaleFactor: 1.2
12 |
13 | # ORB Extractor: Number of levels in the scale pyramid
14 | ORBextractor.nLevels: 8
15 |
16 | # ORB Extractor: Fast threshold
17 | # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
18 | # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
19 | # You can lower these values if your images have low contrast
20 | ORBextractor.iniThFAST: 20
21 | ORBextractor.minThFAST: 7
22 |
--------------------------------------------------------------------------------
/screenshots/1.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/liuzhenboo/orb-extractor/538dbab86a60fd6632b4d222819fe2058332fcc2/screenshots/1.jpg
--------------------------------------------------------------------------------
/screenshots/2.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/liuzhenboo/orb-extractor/538dbab86a60fd6632b4d222819fe2058332fcc2/screenshots/2.jpg
--------------------------------------------------------------------------------
/screenshots/liu1.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/liuzhenboo/orb-extractor/538dbab86a60fd6632b4d222819fe2058332fcc2/screenshots/liu1.jpg
--------------------------------------------------------------------------------
/screenshots/liu2.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/liuzhenboo/orb-extractor/538dbab86a60fd6632b4d222819fe2058332fcc2/screenshots/liu2.jpg
--------------------------------------------------------------------------------
/src/ORBextractor:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/liuzhenboo/orb-extractor/538dbab86a60fd6632b4d222819fe2058332fcc2/src/ORBextractor
--------------------------------------------------------------------------------
/src/ORBextractor.cpp:
--------------------------------------------------------------------------------
1 | #include
2 | #include
3 | #include
4 | #include
5 | #include
6 | #include
7 |
8 | #include "ORBextractor.h"
9 | #include
10 |
11 |
12 | using namespace cv;
13 | using namespace std;
14 |
15 | namespace ORB_SLAM2
16 | {
17 |
18 | const int PATCH_SIZE = 31;
19 | const int HALF_PATCH_SIZE = 15;
20 | const int EDGE_THRESHOLD = 19;
21 |
22 |
23 | static float IC_Angle(const Mat& image, Point2f pt, const vector & u_max)
24 | {
25 | int m_01 = 0, m_10 = 0;
26 |
27 | const uchar* center = &image.at (cvRound(pt.y), cvRound(pt.x));
28 |
29 | // Treat the center line differently, v=0
30 | for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u)
31 | m_10 += u * center[u];
32 |
33 | // Go line by line in the circuI853lar patch
34 | int step = (int)image.step1();
35 | for (int v = 1; v <= HALF_PATCH_SIZE; ++v)
36 | {
37 | // Proceed over the two lines
38 | int v_sum = 0;
39 | int d = u_max[v];
40 | for (int u = -d; u <= d; ++u)
41 | {
42 | int val_plus = center[u + v*step], val_minus = center[u - v*step];
43 | v_sum += (val_plus - val_minus);
44 | m_10 += u * (val_plus + val_minus);
45 | }
46 | m_01 += v * v_sum;
47 | }
48 |
49 | return fastAtan2((float)m_01, (float)m_10);
50 | }
51 |
52 |
53 | const float factorPI = (float)(CV_PI/180.f);
54 | static void computeOrbDescriptor(const KeyPoint& kpt,
55 | const Mat& img, const Point* pattern,
56 | uchar* desc)
57 | {
58 | float angle = (float)kpt.angle*factorPI;
59 | float a = (float)cos(angle), b = (float)sin(angle);
60 |
61 | const uchar* center = &img.at(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
62 | const int step = (int)img.step;
63 |
64 | #define GET_VALUE(idx) \
65 | center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \
66 | cvRound(pattern[idx].x*a - pattern[idx].y*b)]
67 |
68 |
69 | for (int i = 0; i < 32; ++i, pattern += 16)
70 | {
71 | int t0, t1, val;
72 | t0 = GET_VALUE(0); t1 = GET_VALUE(1);
73 | val = t0 < t1;
74 | t0 = GET_VALUE(2); t1 = GET_VALUE(3);
75 | val |= (t0 < t1) << 1;
76 | t0 = GET_VALUE(4); t1 = GET_VALUE(5);
77 | val |= (t0 < t1) << 2;
78 | t0 = GET_VALUE(6); t1 = GET_VALUE(7);
79 | val |= (t0 < t1) << 3;
80 | t0 = GET_VALUE(8); t1 = GET_VALUE(9);
81 | val |= (t0 < t1) << 4;
82 | t0 = GET_VALUE(10); t1 = GET_VALUE(11);
83 | val |= (t0 < t1) << 5;
84 | t0 = GET_VALUE(12); t1 = GET_VALUE(13);
85 | val |= (t0 < t1) << 6;
86 | t0 = GET_VALUE(14); t1 = GET_VALUE(15);
87 | val |= (t0 < t1) << 7;
88 |
89 | desc[i] = (uchar)val;
90 | }
91 |
92 | #undef GET_VALUE
93 | }
94 |
95 |
96 | static int bit_pattern_31_[256*4] =
97 | {
98 | 8,-3, 9,5/*mean (0), correlation (0)*/,
99 | 4,2, 7,-12/*mean (1.12461e-05), correlation (0.0437584)*/,
100 | -11,9, -8,2/*mean (3.37382e-05), correlation (0.0617409)*/,
101 | 7,-12, 12,-13/*mean (5.62303e-05), correlation (0.0636977)*/,
102 | 2,-13, 2,12/*mean (0.000134953), correlation (0.085099)*/,
103 | 1,-7, 1,6/*mean (0.000528565), correlation (0.0857175)*/,
104 | -2,-10, -2,-4/*mean (0.0188821), correlation (0.0985774)*/,
105 | -13,-13, -11,-8/*mean (0.0363135), correlation (0.0899616)*/,
106 | -13,-3, -12,-9/*mean (0.121806), correlation (0.099849)*/,
107 | 10,4, 11,9/*mean (0.122065), correlation (0.093285)*/,
108 | -13,-8, -8,-9/*mean (0.162787), correlation (0.0942748)*/,
109 | -11,7, -9,12/*mean (0.21561), correlation (0.0974438)*/,
110 | 7,7, 12,6/*mean (0.160583), correlation (0.130064)*/,
111 | -4,-5, -3,0/*mean (0.228171), correlation (0.132998)*/,
112 | -13,2, -12,-3/*mean (0.00997526), correlation (0.145926)*/,
113 | -9,0, -7,5/*mean (0.198234), correlation (0.143636)*/,
114 | 12,-6, 12,-1/*mean (0.0676226), correlation (0.16689)*/,
115 | -3,6, -2,12/*mean (0.166847), correlation (0.171682)*/,
116 | -6,-13, -4,-8/*mean (0.101215), correlation (0.179716)*/,
117 | 11,-13, 12,-8/*mean (0.200641), correlation (0.192279)*/,
118 | 4,7, 5,1/*mean (0.205106), correlation (0.186848)*/,
119 | 5,-3, 10,-3/*mean (0.234908), correlation (0.192319)*/,
120 | 3,-7, 6,12/*mean (0.0709964), correlation (0.210872)*/,
121 | -8,-7, -6,-2/*mean (0.0939834), correlation (0.212589)*/,
122 | -2,11, -1,-10/*mean (0.127778), correlation (0.20866)*/,
123 | -13,12, -8,10/*mean (0.14783), correlation (0.206356)*/,
124 | -7,3, -5,-3/*mean (0.182141), correlation (0.198942)*/,
125 | -4,2, -3,7/*mean (0.188237), correlation (0.21384)*/,
126 | -10,-12, -6,11/*mean (0.14865), correlation (0.23571)*/,
127 | 5,-12, 6,-7/*mean (0.222312), correlation (0.23324)*/,
128 | 5,-6, 7,-1/*mean (0.229082), correlation (0.23389)*/,
129 | 1,0, 4,-5/*mean (0.241577), correlation (0.215286)*/,
130 | 9,11, 11,-13/*mean (0.00338507), correlation (0.251373)*/,
131 | 4,7, 4,12/*mean (0.131005), correlation (0.257622)*/,
132 | 2,-1, 4,4/*mean (0.152755), correlation (0.255205)*/,
133 | -4,-12, -2,7/*mean (0.182771), correlation (0.244867)*/,
134 | -8,-5, -7,-10/*mean (0.186898), correlation (0.23901)*/,
135 | 4,11, 9,12/*mean (0.226226), correlation (0.258255)*/,
136 | 0,-8, 1,-13/*mean (0.0897886), correlation (0.274827)*/,
137 | -13,-2, -8,2/*mean (0.148774), correlation (0.28065)*/,
138 | -3,-2, -2,3/*mean (0.153048), correlation (0.283063)*/,
139 | -6,9, -4,-9/*mean (0.169523), correlation (0.278248)*/,
140 | 8,12, 10,7/*mean (0.225337), correlation (0.282851)*/,
141 | 0,9, 1,3/*mean (0.226687), correlation (0.278734)*/,
142 | 7,-5, 11,-10/*mean (0.00693882), correlation (0.305161)*/,
143 | -13,-6, -11,0/*mean (0.0227283), correlation (0.300181)*/,
144 | 10,7, 12,1/*mean (0.125517), correlation (0.31089)*/,
145 | -6,-3, -6,12/*mean (0.131748), correlation (0.312779)*/,
146 | 10,-9, 12,-4/*mean (0.144827), correlation (0.292797)*/,
147 | -13,8, -8,-12/*mean (0.149202), correlation (0.308918)*/,
148 | -13,0, -8,-4/*mean (0.160909), correlation (0.310013)*/,
149 | 3,3, 7,8/*mean (0.177755), correlation (0.309394)*/,
150 | 5,7, 10,-7/*mean (0.212337), correlation (0.310315)*/,
151 | -1,7, 1,-12/*mean (0.214429), correlation (0.311933)*/,
152 | 3,-10, 5,6/*mean (0.235807), correlation (0.313104)*/,
153 | 2,-4, 3,-10/*mean (0.00494827), correlation (0.344948)*/,
154 | -13,0, -13,5/*mean (0.0549145), correlation (0.344675)*/,
155 | -13,-7, -12,12/*mean (0.103385), correlation (0.342715)*/,
156 | -13,3, -11,8/*mean (0.134222), correlation (0.322922)*/,
157 | -7,12, -4,7/*mean (0.153284), correlation (0.337061)*/,
158 | 6,-10, 12,8/*mean (0.154881), correlation (0.329257)*/,
159 | -9,-1, -7,-6/*mean (0.200967), correlation (0.33312)*/,
160 | -2,-5, 0,12/*mean (0.201518), correlation (0.340635)*/,
161 | -12,5, -7,5/*mean (0.207805), correlation (0.335631)*/,
162 | 3,-10, 8,-13/*mean (0.224438), correlation (0.34504)*/,
163 | -7,-7, -4,5/*mean (0.239361), correlation (0.338053)*/,
164 | -3,-2, -1,-7/*mean (0.240744), correlation (0.344322)*/,
165 | 2,9, 5,-11/*mean (0.242949), correlation (0.34145)*/,
166 | -11,-13, -5,-13/*mean (0.244028), correlation (0.336861)*/,
167 | -1,6, 0,-1/*mean (0.247571), correlation (0.343684)*/,
168 | 5,-3, 5,2/*mean (0.000697256), correlation (0.357265)*/,
169 | -4,-13, -4,12/*mean (0.00213675), correlation (0.373827)*/,
170 | -9,-6, -9,6/*mean (0.0126856), correlation (0.373938)*/,
171 | -12,-10, -8,-4/*mean (0.0152497), correlation (0.364237)*/,
172 | 10,2, 12,-3/*mean (0.0299933), correlation (0.345292)*/,
173 | 7,12, 12,12/*mean (0.0307242), correlation (0.366299)*/,
174 | -7,-13, -6,5/*mean (0.0534975), correlation (0.368357)*/,
175 | -4,9, -3,4/*mean (0.099865), correlation (0.372276)*/,
176 | 7,-1, 12,2/*mean (0.117083), correlation (0.364529)*/,
177 | -7,6, -5,1/*mean (0.126125), correlation (0.369606)*/,
178 | -13,11, -12,5/*mean (0.130364), correlation (0.358502)*/,
179 | -3,7, -2,-6/*mean (0.131691), correlation (0.375531)*/,
180 | 7,-8, 12,-7/*mean (0.160166), correlation (0.379508)*/,
181 | -13,-7, -11,-12/*mean (0.167848), correlation (0.353343)*/,
182 | 1,-3, 12,12/*mean (0.183378), correlation (0.371916)*/,
183 | 2,-6, 3,0/*mean (0.228711), correlation (0.371761)*/,
184 | -4,3, -2,-13/*mean (0.247211), correlation (0.364063)*/,
185 | -1,-13, 1,9/*mean (0.249325), correlation (0.378139)*/,
186 | 7,1, 8,-6/*mean (0.000652272), correlation (0.411682)*/,
187 | 1,-1, 3,12/*mean (0.00248538), correlation (0.392988)*/,
188 | 9,1, 12,6/*mean (0.0206815), correlation (0.386106)*/,
189 | -1,-9, -1,3/*mean (0.0364485), correlation (0.410752)*/,
190 | -13,-13, -10,5/*mean (0.0376068), correlation (0.398374)*/,
191 | 7,7, 10,12/*mean (0.0424202), correlation (0.405663)*/,
192 | 12,-5, 12,9/*mean (0.0942645), correlation (0.410422)*/,
193 | 6,3, 7,11/*mean (0.1074), correlation (0.413224)*/,
194 | 5,-13, 6,10/*mean (0.109256), correlation (0.408646)*/,
195 | 2,-12, 2,3/*mean (0.131691), correlation (0.416076)*/,
196 | 3,8, 4,-6/*mean (0.165081), correlation (0.417569)*/,
197 | 2,6, 12,-13/*mean (0.171874), correlation (0.408471)*/,
198 | 9,-12, 10,3/*mean (0.175146), correlation (0.41296)*/,
199 | -8,4, -7,9/*mean (0.183682), correlation (0.402956)*/,
200 | -11,12, -4,-6/*mean (0.184672), correlation (0.416125)*/,
201 | 1,12, 2,-8/*mean (0.191487), correlation (0.386696)*/,
202 | 6,-9, 7,-4/*mean (0.192668), correlation (0.394771)*/,
203 | 2,3, 3,-2/*mean (0.200157), correlation (0.408303)*/,
204 | 6,3, 11,0/*mean (0.204588), correlation (0.411762)*/,
205 | 3,-3, 8,-8/*mean (0.205904), correlation (0.416294)*/,
206 | 7,8, 9,3/*mean (0.213237), correlation (0.409306)*/,
207 | -11,-5, -6,-4/*mean (0.243444), correlation (0.395069)*/,
208 | -10,11, -5,10/*mean (0.247672), correlation (0.413392)*/,
209 | -5,-8, -3,12/*mean (0.24774), correlation (0.411416)*/,
210 | -10,5, -9,0/*mean (0.00213675), correlation (0.454003)*/,
211 | 8,-1, 12,-6/*mean (0.0293635), correlation (0.455368)*/,
212 | 4,-6, 6,-11/*mean (0.0404971), correlation (0.457393)*/,
213 | -10,12, -8,7/*mean (0.0481107), correlation (0.448364)*/,
214 | 4,-2, 6,7/*mean (0.050641), correlation (0.455019)*/,
215 | -2,0, -2,12/*mean (0.0525978), correlation (0.44338)*/,
216 | -5,-8, -5,2/*mean (0.0629667), correlation (0.457096)*/,
217 | 7,-6, 10,12/*mean (0.0653846), correlation (0.445623)*/,
218 | -9,-13, -8,-8/*mean (0.0858749), correlation (0.449789)*/,
219 | -5,-13, -5,-2/*mean (0.122402), correlation (0.450201)*/,
220 | 8,-8, 9,-13/*mean (0.125416), correlation (0.453224)*/,
221 | -9,-11, -9,0/*mean (0.130128), correlation (0.458724)*/,
222 | 1,-8, 1,-2/*mean (0.132467), correlation (0.440133)*/,
223 | 7,-4, 9,1/*mean (0.132692), correlation (0.454)*/,
224 | -2,1, -1,-4/*mean (0.135695), correlation (0.455739)*/,
225 | 11,-6, 12,-11/*mean (0.142904), correlation (0.446114)*/,
226 | -12,-9, -6,4/*mean (0.146165), correlation (0.451473)*/,
227 | 3,7, 7,12/*mean (0.147627), correlation (0.456643)*/,
228 | 5,5, 10,8/*mean (0.152901), correlation (0.455036)*/,
229 | 0,-4, 2,8/*mean (0.167083), correlation (0.459315)*/,
230 | -9,12, -5,-13/*mean (0.173234), correlation (0.454706)*/,
231 | 0,7, 2,12/*mean (0.18312), correlation (0.433855)*/,
232 | -1,2, 1,7/*mean (0.185504), correlation (0.443838)*/,
233 | 5,11, 7,-9/*mean (0.185706), correlation (0.451123)*/,
234 | 3,5, 6,-8/*mean (0.188968), correlation (0.455808)*/,
235 | -13,-4, -8,9/*mean (0.191667), correlation (0.459128)*/,
236 | -5,9, -3,-3/*mean (0.193196), correlation (0.458364)*/,
237 | -4,-7, -3,-12/*mean (0.196536), correlation (0.455782)*/,
238 | 6,5, 8,0/*mean (0.1972), correlation (0.450481)*/,
239 | -7,6, -6,12/*mean (0.199438), correlation (0.458156)*/,
240 | -13,6, -5,-2/*mean (0.211224), correlation (0.449548)*/,
241 | 1,-10, 3,10/*mean (0.211718), correlation (0.440606)*/,
242 | 4,1, 8,-4/*mean (0.213034), correlation (0.443177)*/,
243 | -2,-2, 2,-13/*mean (0.234334), correlation (0.455304)*/,
244 | 2,-12, 12,12/*mean (0.235684), correlation (0.443436)*/,
245 | -2,-13, 0,-6/*mean (0.237674), correlation (0.452525)*/,
246 | 4,1, 9,3/*mean (0.23962), correlation (0.444824)*/,
247 | -6,-10, -3,-5/*mean (0.248459), correlation (0.439621)*/,
248 | -3,-13, -1,1/*mean (0.249505), correlation (0.456666)*/,
249 | 7,5, 12,-11/*mean (0.00119208), correlation (0.495466)*/,
250 | 4,-2, 5,-7/*mean (0.00372245), correlation (0.484214)*/,
251 | -13,9, -9,-5/*mean (0.00741116), correlation (0.499854)*/,
252 | 7,1, 8,6/*mean (0.0208952), correlation (0.499773)*/,
253 | 7,-8, 7,6/*mean (0.0220085), correlation (0.501609)*/,
254 | -7,-4, -7,1/*mean (0.0233806), correlation (0.496568)*/,
255 | -8,11, -7,-8/*mean (0.0236505), correlation (0.489719)*/,
256 | -13,6, -12,-8/*mean (0.0268781), correlation (0.503487)*/,
257 | 2,4, 3,9/*mean (0.0323324), correlation (0.501938)*/,
258 | 10,-5, 12,3/*mean (0.0399235), correlation (0.494029)*/,
259 | -6,-5, -6,7/*mean (0.0420153), correlation (0.486579)*/,
260 | 8,-3, 9,-8/*mean (0.0548021), correlation (0.484237)*/,
261 | 2,-12, 2,8/*mean (0.0616622), correlation (0.496642)*/,
262 | -11,-2, -10,3/*mean (0.0627755), correlation (0.498563)*/,
263 | -12,-13, -7,-9/*mean (0.0829622), correlation (0.495491)*/,
264 | -11,0, -10,-5/*mean (0.0843342), correlation (0.487146)*/,
265 | 5,-3, 11,8/*mean (0.0929937), correlation (0.502315)*/,
266 | -2,-13, -1,12/*mean (0.113327), correlation (0.48941)*/,
267 | -1,-8, 0,9/*mean (0.132119), correlation (0.467268)*/,
268 | -13,-11, -12,-5/*mean (0.136269), correlation (0.498771)*/,
269 | -10,-2, -10,11/*mean (0.142173), correlation (0.498714)*/,
270 | -3,9, -2,-13/*mean (0.144141), correlation (0.491973)*/,
271 | 2,-3, 3,2/*mean (0.14892), correlation (0.500782)*/,
272 | -9,-13, -4,0/*mean (0.150371), correlation (0.498211)*/,
273 | -4,6, -3,-10/*mean (0.152159), correlation (0.495547)*/,
274 | -4,12, -2,-7/*mean (0.156152), correlation (0.496925)*/,
275 | -6,-11, -4,9/*mean (0.15749), correlation (0.499222)*/,
276 | 6,-3, 6,11/*mean (0.159211), correlation (0.503821)*/,
277 | -13,11, -5,5/*mean (0.162427), correlation (0.501907)*/,
278 | 11,11, 12,6/*mean (0.16652), correlation (0.497632)*/,
279 | 7,-5, 12,-2/*mean (0.169141), correlation (0.484474)*/,
280 | -1,12, 0,7/*mean (0.169456), correlation (0.495339)*/,
281 | -4,-8, -3,-2/*mean (0.171457), correlation (0.487251)*/,
282 | -7,1, -6,7/*mean (0.175), correlation (0.500024)*/,
283 | -13,-12, -8,-13/*mean (0.175866), correlation (0.497523)*/,
284 | -7,-2, -6,-8/*mean (0.178273), correlation (0.501854)*/,
285 | -8,5, -6,-9/*mean (0.181107), correlation (0.494888)*/,
286 | -5,-1, -4,5/*mean (0.190227), correlation (0.482557)*/,
287 | -13,7, -8,10/*mean (0.196739), correlation (0.496503)*/,
288 | 1,5, 5,-13/*mean (0.19973), correlation (0.499759)*/,
289 | 1,0, 10,-13/*mean (0.204465), correlation (0.49873)*/,
290 | 9,12, 10,-1/*mean (0.209334), correlation (0.49063)*/,
291 | 5,-8, 10,-9/*mean (0.211134), correlation (0.503011)*/,
292 | -1,11, 1,-13/*mean (0.212), correlation (0.499414)*/,
293 | -9,-3, -6,2/*mean (0.212168), correlation (0.480739)*/,
294 | -1,-10, 1,12/*mean (0.212731), correlation (0.502523)*/,
295 | -13,1, -8,-10/*mean (0.21327), correlation (0.489786)*/,
296 | 8,-11, 10,-6/*mean (0.214159), correlation (0.488246)*/,
297 | 2,-13, 3,-6/*mean (0.216993), correlation (0.50287)*/,
298 | 7,-13, 12,-9/*mean (0.223639), correlation (0.470502)*/,
299 | -10,-10, -5,-7/*mean (0.224089), correlation (0.500852)*/,
300 | -10,-8, -8,-13/*mean (0.228666), correlation (0.502629)*/,
301 | 4,-6, 8,5/*mean (0.22906), correlation (0.498305)*/,
302 | 3,12, 8,-13/*mean (0.233378), correlation (0.503825)*/,
303 | -4,2, -3,-3/*mean (0.234323), correlation (0.476692)*/,
304 | 5,-13, 10,-12/*mean (0.236392), correlation (0.475462)*/,
305 | 4,-13, 5,-1/*mean (0.236842), correlation (0.504132)*/,
306 | -9,9, -4,3/*mean (0.236977), correlation (0.497739)*/,
307 | 0,3, 3,-9/*mean (0.24314), correlation (0.499398)*/,
308 | -12,1, -6,1/*mean (0.243297), correlation (0.489447)*/,
309 | 3,2, 4,-8/*mean (0.00155196), correlation (0.553496)*/,
310 | -10,-10, -10,9/*mean (0.00239541), correlation (0.54297)*/,
311 | 8,-13, 12,12/*mean (0.0034413), correlation (0.544361)*/,
312 | -8,-12, -6,-5/*mean (0.003565), correlation (0.551225)*/,
313 | 2,2, 3,7/*mean (0.00835583), correlation (0.55285)*/,
314 | 10,6, 11,-8/*mean (0.00885065), correlation (0.540913)*/,
315 | 6,8, 8,-12/*mean (0.0101552), correlation (0.551085)*/,
316 | -7,10, -6,5/*mean (0.0102227), correlation (0.533635)*/,
317 | -3,-9, -3,9/*mean (0.0110211), correlation (0.543121)*/,
318 | -1,-13, -1,5/*mean (0.0113473), correlation (0.550173)*/,
319 | -3,-7, -3,4/*mean (0.0140913), correlation (0.554774)*/,
320 | -8,-2, -8,3/*mean (0.017049), correlation (0.55461)*/,
321 | 4,2, 12,12/*mean (0.01778), correlation (0.546921)*/,
322 | 2,-5, 3,11/*mean (0.0224022), correlation (0.549667)*/,
323 | 6,-9, 11,-13/*mean (0.029161), correlation (0.546295)*/,
324 | 3,-1, 7,12/*mean (0.0303081), correlation (0.548599)*/,
325 | 11,-1, 12,4/*mean (0.0355151), correlation (0.523943)*/,
326 | -3,0, -3,6/*mean (0.0417904), correlation (0.543395)*/,
327 | 4,-11, 4,12/*mean (0.0487292), correlation (0.542818)*/,
328 | 2,-4, 2,1/*mean (0.0575124), correlation (0.554888)*/,
329 | -10,-6, -8,1/*mean (0.0594242), correlation (0.544026)*/,
330 | -13,7, -11,1/*mean (0.0597391), correlation (0.550524)*/,
331 | -13,12, -11,-13/*mean (0.0608974), correlation (0.55383)*/,
332 | 6,0, 11,-13/*mean (0.065126), correlation (0.552006)*/,
333 | 0,-1, 1,4/*mean (0.074224), correlation (0.546372)*/,
334 | -13,3, -9,-2/*mean (0.0808592), correlation (0.554875)*/,
335 | -9,8, -6,-3/*mean (0.0883378), correlation (0.551178)*/,
336 | -13,-6, -8,-2/*mean (0.0901035), correlation (0.548446)*/,
337 | 5,-9, 8,10/*mean (0.0949843), correlation (0.554694)*/,
338 | 2,7, 3,-9/*mean (0.0994152), correlation (0.550979)*/,
339 | -1,-6, -1,-1/*mean (0.10045), correlation (0.552714)*/,
340 | 9,5, 11,-2/*mean (0.100686), correlation (0.552594)*/,
341 | 11,-3, 12,-8/*mean (0.101091), correlation (0.532394)*/,
342 | 3,0, 3,5/*mean (0.101147), correlation (0.525576)*/,
343 | -1,4, 0,10/*mean (0.105263), correlation (0.531498)*/,
344 | 3,-6, 4,5/*mean (0.110785), correlation (0.540491)*/,
345 | -13,0, -10,5/*mean (0.112798), correlation (0.536582)*/,
346 | 5,8, 12,11/*mean (0.114181), correlation (0.555793)*/,
347 | 8,9, 9,-6/*mean (0.117431), correlation (0.553763)*/,
348 | 7,-4, 8,-12/*mean (0.118522), correlation (0.553452)*/,
349 | -10,4, -10,9/*mean (0.12094), correlation (0.554785)*/,
350 | 7,3, 12,4/*mean (0.122582), correlation (0.555825)*/,
351 | 9,-7, 10,-2/*mean (0.124978), correlation (0.549846)*/,
352 | 7,0, 12,-2/*mean (0.127002), correlation (0.537452)*/,
353 | -1,-6, 0,-11/*mean (0.127148), correlation (0.547401)*/
354 | };
355 |
356 | ORBextractor::ORBextractor(int _nfeatures, float _scaleFactor, int _nlevels,
357 | int _iniThFAST, int _minThFAST):
358 | nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
359 | iniThFAST(_iniThFAST), minThFAST(_minThFAST)
360 | {
361 | mvScaleFactor.resize(nlevels);
362 | mvLevelSigma2.resize(nlevels);
363 | mvScaleFactor[0]=1.0f;
364 | mvLevelSigma2[0]=1.0f;
365 | for(int i=1; i= vmin; --v)
410 | {
411 | while (umax[v0] == umax[v0 + 1])
412 | ++v0;
413 | umax[v] = v0;
414 | ++v0;
415 | }
416 | }
417 |
418 | static void computeOrientation(const Mat& image, vector& keypoints, const vector& umax)
419 | {
420 | for (vector::iterator keypoint = keypoints.begin(),
421 | keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
422 | {
423 | keypoint->angle = IC_Angle(image, keypoint->pt, umax);
424 | }
425 | }
426 |
427 | void ExtractorNode::DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4)
428 | {
429 | const int halfX = ceil(static_cast(UR.x-UL.x)/2);
430 | const int halfY = ceil(static_cast(BR.y-UL.y)/2);
431 |
432 | //Define boundaries of childs
433 | n1.UL = UL;
434 | n1.UR = cv::Point2i(UL.x+halfX,UL.y);
435 | n1.BL = cv::Point2i(UL.x,UL.y+halfY);
436 | n1.BR = cv::Point2i(UL.x+halfX,UL.y+halfY);
437 | n1.vKeys.reserve(vKeys.size());
438 |
439 | n2.UL = n1.UR;
440 | n2.UR = UR;
441 | n2.BL = n1.BR;
442 | n2.BR = cv::Point2i(UR.x,UL.y+halfY);
443 | n2.vKeys.reserve(vKeys.size());
444 |
445 | n3.UL = n1.BL;
446 | n3.UR = n1.BR;
447 | n3.BL = BL;
448 | n3.BR = cv::Point2i(n1.BR.x,BL.y);
449 | n3.vKeys.reserve(vKeys.size());
450 |
451 | n4.UL = n3.UR;
452 | n4.UR = n2.BR;
453 | n4.BL = n3.BR;
454 | n4.BR = BR;
455 | n4.vKeys.reserve(vKeys.size());
456 |
457 | //Associate points to childs
458 | for(size_t i=0;i ORBextractor::DistributeOctTree(const vector& vToDistributeKeys, const int &minX,
486 | const int &maxX, const int &minY, const int &maxY, const int &N, const int &level)
487 | {
488 | // Compute how many initial nodes
489 | const int nIni = round(static_cast(maxX-minX)/(maxY-minY));
490 |
491 | const float hX = static_cast(maxX-minX)/nIni;
492 |
493 | list lNodes;
494 |
495 | vector vpIniNodes;
496 | vpIniNodes.resize(nIni);
497 |
498 | for(int i=0; i(i),0);
502 | ni.UR = cv::Point2i(hX*static_cast(i+1),0);
503 | ni.BL = cv::Point2i(ni.UL.x,maxY-minY);
504 | ni.BR = cv::Point2i(ni.UR.x,maxY-minY);
505 | ni.vKeys.reserve(vToDistributeKeys.size());
506 |
507 | lNodes.push_back(ni);
508 | vpIniNodes[i] = &lNodes.back();
509 | }
510 |
511 | //Associate points to childs
512 | for(size_t i=0;ivKeys.push_back(kp);
516 | }
517 |
518 | list::iterator lit = lNodes.begin();
519 |
520 | while(lit!=lNodes.end())
521 | {
522 | if(lit->vKeys.size()==1)
523 | {
524 | lit->bNoMore=true;
525 | lit++;
526 | }
527 | else if(lit->vKeys.empty())
528 | lit = lNodes.erase(lit);
529 | else
530 | lit++;
531 | }
532 |
533 | bool bFinish = false;
534 |
535 | int iteration = 0;
536 |
537 | vector > vSizeAndPointerToNode;
538 | vSizeAndPointerToNode.reserve(lNodes.size()*4);
539 |
540 | // 根据兴趣点分布,利用N叉树方法对图像进行划分区域
541 | while(!bFinish)
542 | {
543 | iteration++;
544 |
545 | int prevSize = lNodes.size();
546 |
547 | lit = lNodes.begin();
548 |
549 | int nToExpand = 0;
550 |
551 | vSizeAndPointerToNode.clear();
552 |
553 | // 将目前的子区域经行划分
554 | while(lit!=lNodes.end())
555 | {
556 | if(lit->bNoMore)
557 | {
558 | // If node only contains one point do not subdivide and continue
559 | lit++;
560 | continue;
561 | }
562 | else
563 | {
564 | // If more than one point, subdivide
565 | ExtractorNode n1,n2,n3,n4;
566 | lit->DivideNode(n1,n2,n3,n4); // 再细分成四个子区域
567 |
568 | // Add childs if they contain points
569 | if(n1.vKeys.size()>0)
570 | {
571 | lNodes.push_front(n1);
572 | if(n1.vKeys.size()>1)
573 | {
574 | nToExpand++;
575 | vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
576 | lNodes.front().lit = lNodes.begin();
577 | }
578 | }
579 | if(n2.vKeys.size()>0)
580 | {
581 | lNodes.push_front(n2);
582 | if(n2.vKeys.size()>1)
583 | {
584 | nToExpand++;
585 | vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
586 | lNodes.front().lit = lNodes.begin();
587 | }
588 | }
589 | if(n3.vKeys.size()>0)
590 | {
591 | lNodes.push_front(n3);
592 | if(n3.vKeys.size()>1)
593 | {
594 | nToExpand++;
595 | vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
596 | lNodes.front().lit = lNodes.begin();
597 | }
598 | }
599 | if(n4.vKeys.size()>0)
600 | {
601 | lNodes.push_front(n4);
602 | if(n4.vKeys.size()>1)
603 | {
604 | nToExpand++;
605 | vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
606 | lNodes.front().lit = lNodes.begin();
607 | }
608 | }
609 |
610 | lit=lNodes.erase(lit);
611 | continue;
612 | }
613 | }
614 |
615 | // Finish if there are more nodes than required features
616 | // or all nodes contain just one point
617 | if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
618 | {
619 | bFinish = true;
620 | }
621 | // 当再划分之后所有的Node数大于要求数目时
622 | else if(((int)lNodes.size()+nToExpand*3)>N)
623 | {
624 |
625 | while(!bFinish)
626 | {
627 |
628 | prevSize = lNodes.size();
629 |
630 | vector > vPrevSizeAndPointerToNode = vSizeAndPointerToNode;
631 | vSizeAndPointerToNode.clear();
632 |
633 | // 对需要划分的部分进行排序, 即对兴趣点数较多的区域进行划分
634 | sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end());
635 | for(int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--)
636 | {
637 | ExtractorNode n1,n2,n3,n4;
638 | vPrevSizeAndPointerToNode[j].second->DivideNode(n1,n2,n3,n4);
639 |
640 | // Add childs if they contain points
641 | if(n1.vKeys.size()>0)
642 | {
643 | lNodes.push_front(n1);
644 | if(n1.vKeys.size()>1)
645 | {
646 | vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
647 | lNodes.front().lit = lNodes.begin();
648 | }
649 | }
650 | if(n2.vKeys.size()>0)
651 | {
652 | lNodes.push_front(n2);
653 | if(n2.vKeys.size()>1)
654 | {
655 | vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
656 | lNodes.front().lit = lNodes.begin();
657 | }
658 | }
659 | if(n3.vKeys.size()>0)
660 | {
661 | lNodes.push_front(n3);
662 | if(n3.vKeys.size()>1)
663 | {
664 | vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
665 | lNodes.front().lit = lNodes.begin();
666 | }
667 | }
668 | if(n4.vKeys.size()>0)
669 | {
670 | lNodes.push_front(n4);
671 | if(n4.vKeys.size()>1)
672 | {
673 | vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
674 | lNodes.front().lit = lNodes.begin();
675 | }
676 | }
677 |
678 | lNodes.erase(vPrevSizeAndPointerToNode[j].second->lit);
679 |
680 | if((int)lNodes.size()>=N)
681 | break;
682 | }
683 |
684 | if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
685 | bFinish = true;
686 |
687 | }
688 | }
689 | }
690 |
691 | // Retain the best point in each node
692 | // 保留每个区域响应值最大的一个兴趣点
693 | vector vResultKeys;
694 | vResultKeys.reserve(nfeatures);
695 | for(list::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++)
696 | {
697 | vector &vNodeKeys = lit->vKeys;
698 | cv::KeyPoint* pKP = &vNodeKeys[0];
699 | float maxResponse = pKP->response;
700 |
701 | for(size_t k=1;kmaxResponse)
704 | {
705 | pKP = &vNodeKeys[k];
706 | maxResponse = vNodeKeys[k].response;
707 | }
708 | }
709 |
710 | vResultKeys.push_back(*pKP);
711 | }
712 |
713 | return vResultKeys;
714 | }
715 |
716 | void ORBextractor::ComputeKeyPointsOctTree(vector >& allKeypoints)
717 | {
718 | allKeypoints.resize(nlevels);
719 |
720 | const float W = 30;
721 |
722 | // 对每一层图像做处理
723 | for (int level = 0; level < nlevels; ++level)
724 | {
725 | const int minBorderX = EDGE_THRESHOLD-3;
726 | const int minBorderY = minBorderX;
727 | const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
728 | const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;
729 |
730 | vector vToDistributeKeys;
731 | vToDistributeKeys.reserve(nfeatures*10);
732 |
733 | const float width = (maxBorderX-minBorderX);
734 | const float height = (maxBorderY-minBorderY);
735 |
736 | const int nCols = width/W;
737 | const int nRows = height/W;
738 | const int wCell = ceil(width/nCols);
739 | const int hCell = ceil(height/nRows);
740 |
741 | for(int i=0; i=maxBorderY-3)
747 | continue;
748 | if(maxY>maxBorderY)
749 | maxY = maxBorderY;
750 |
751 | for(int j=0; j=maxBorderX-6)
756 | continue;
757 | if(maxX>maxBorderX)
758 | maxX = maxBorderX;
759 |
760 | // FAST提取兴趣点, 自适应阈值
761 | vector vKeysCell;
762 | FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
763 | vKeysCell,iniThFAST,true);
764 |
765 | if(vKeysCell.empty())
766 | {
767 | FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
768 | vKeysCell,minThFAST,true);
769 | }
770 |
771 | if(!vKeysCell.empty())
772 | {
773 | for(vector::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
774 | {
775 | (*vit).pt.x+=j*wCell;
776 | (*vit).pt.y+=i*hCell;
777 | vToDistributeKeys.push_back(*vit);
778 | }
779 | }
780 |
781 | }
782 | }
783 |
784 | vector & keypoints = allKeypoints[level];
785 | keypoints.reserve(nfeatures);
786 |
787 | // 根据mnFeaturesPerLevel,即该层的兴趣点数,对特征点进行剔除
788 | keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
789 | minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);
790 |
791 | const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
792 |
793 | // Add border to coordinates and scale information
794 | const int nkps = keypoints.size();
795 | for(int i=0; i > &allKeypoints)
810 | {
811 | allKeypoints.resize(nlevels);
812 |
813 | float imageRatio = (float)mvImagePyramid[0].cols/mvImagePyramid[0].rows;
814 |
815 | for (int level = 0; level < nlevels; ++level)
816 | {
817 | const int nDesiredFeatures = mnFeaturesPerLevel[level];
818 |
819 | const int levelCols = sqrt((float)nDesiredFeatures/(5*imageRatio));
820 | const int levelRows = imageRatio*levelCols;
821 |
822 | const int minBorderX = EDGE_THRESHOLD;
823 | const int minBorderY = minBorderX;
824 | const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD;
825 | const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD;
826 |
827 | const int W = maxBorderX - minBorderX;
828 | const int H = maxBorderY - minBorderY;
829 | const int cellW = ceil((float)W/levelCols);
830 | const int cellH = ceil((float)H/levelRows);
831 |
832 | const int nCells = levelRows*levelCols;
833 | const int nfeaturesCell = ceil((float)nDesiredFeatures/nCells);
834 |
835 | vector > > cellKeyPoints(levelRows, vector >(levelCols));
836 |
837 | vector > nToRetain(levelRows,vector(levelCols,0));
838 | vector > nTotal(levelRows,vector(levelCols,0));
839 | vector > bNoMore(levelRows,vector(levelCols,false));
840 | vector iniXCol(levelCols);
841 | vector iniYRow(levelRows);
842 | int nNoMore = 0;
843 | int nToDistribute = 0;
844 |
845 |
846 | float hY = cellH + 6;
847 |
848 | for(int i=0; infeaturesCell)
903 | {
904 | nToRetain[i][j] = nfeaturesCell;
905 | bNoMore[i][j] = false;
906 | }
907 | else
908 | {
909 | nToRetain[i][j] = nKeys;
910 | nToDistribute += nfeaturesCell-nKeys;
911 | bNoMore[i][j] = true;
912 | nNoMore++;
913 | }
914 |
915 | }
916 | }
917 |
918 |
919 | // Retain by score
920 |
921 | while(nToDistribute>0 && nNoMorenNewFeaturesCell)
933 | {
934 | nToRetain[i][j] = nNewFeaturesCell;
935 | bNoMore[i][j] = false;
936 | }
937 | else
938 | {
939 | nToRetain[i][j] = nTotal[i][j];
940 | nToDistribute += nNewFeaturesCell-nTotal[i][j];
941 | bNoMore[i][j] = true;
942 | nNoMore++;
943 | }
944 | }
945 | }
946 | }
947 | }
948 |
949 | vector & keypoints = allKeypoints[level];
950 | keypoints.reserve(nDesiredFeatures*2);
951 |
952 | const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
953 |
954 | // Retain by score and transform coordinates
955 | for(int i=0; i &keysCell = cellKeyPoints[i][j];
960 | KeyPointsFilter::retainBest(keysCell,nToRetain[i][j]);
961 | if((int)keysCell.size()>nToRetain[i][j])
962 | keysCell.resize(nToRetain[i][j]);
963 |
964 |
965 | for(size_t k=0, kend=keysCell.size(); knDesiredFeatures)
977 | {
978 | KeyPointsFilter::retainBest(keypoints,nDesiredFeatures);
979 | keypoints.resize(nDesiredFeatures);
980 | }
981 | }
982 |
983 | // and compute orientations
984 | for (int level = 0; level < nlevels; ++level)
985 | computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
986 | }
987 |
988 | static void computeDescriptors(const Mat& image, vector& keypoints, Mat& descriptors,
989 | const vector& pattern)
990 | {
991 | descriptors = Mat::zeros((int)keypoints.size(), 32, CV_8UC1);
992 |
993 | for (size_t i = 0; i < keypoints.size(); i++)
994 | computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i));
995 | }
996 |
997 | void ORBextractor::operator()( InputArray _image, InputArray _mask, vector& _keypoints,
998 | OutputArray _descriptors)
999 | {
1000 | if(_image.empty())
1001 | return;
1002 |
1003 | Mat image = _image.getMat();
1004 | assert(image.type() == CV_8UC1 );
1005 |
1006 | // Pre-compute the scale pyramid
1007 | // 构建图像金字塔
1008 | ComputePyramid(image);
1009 |
1010 | // 计算每层图像的兴趣点
1011 | vector < vector > allKeypoints; // vector>
1012 | ComputeKeyPointsOctTree(allKeypoints);
1013 | //ComputeKeyPointsOld(allKeypoints);
1014 |
1015 | Mat descriptors;
1016 |
1017 | int nkeypoints = 0;
1018 | for (int level = 0; level < nlevels; ++level)
1019 | nkeypoints += (int)allKeypoints[level].size();
1020 | if( nkeypoints == 0 )
1021 | _descriptors.release();
1022 | else
1023 | {
1024 | _descriptors.create(nkeypoints, 32, CV_8U);
1025 | descriptors = _descriptors.getMat();
1026 | }
1027 |
1028 | _keypoints.clear();
1029 | _keypoints.reserve(nkeypoints);
1030 |
1031 | int offset = 0;
1032 | for (int level = 0; level < nlevels; ++level)
1033 | {
1034 | vector& keypoints = allKeypoints[level];
1035 | int nkeypointsLevel = (int)keypoints.size();
1036 |
1037 | if(nkeypointsLevel==0)
1038 | continue;
1039 |
1040 | // preprocess the resized image 对图像进行高斯模糊
1041 | Mat workingMat = mvImagePyramid[level].clone();
1042 | GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101);
1043 |
1044 | // Compute the descriptors 计算描述子
1045 | Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);
1046 | computeDescriptors(workingMat, keypoints, desc, pattern);
1047 |
1048 | offset += nkeypointsLevel;
1049 |
1050 | // Scale keypoint coordinates
1051 | if (level != 0)
1052 | {
1053 | float scale = mvScaleFactor[level]; //getScale(level, firstLevel, scaleFactor);
1054 | for (vector::iterator keypoint = keypoints.begin(),
1055 | keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
1056 | keypoint->pt *= scale;
1057 | }
1058 | // And add the keypoints to the output
1059 | _keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
1060 | }
1061 | }
1062 |
1063 | /**
1064 | * 构建图像金字塔
1065 | * @param image 输入图像
1066 | */
1067 | void ORBextractor::ComputePyramid(cv::Mat image)
1068 | {
1069 | for (int level = 0; level < nlevels; ++level)
1070 | {
1071 | float scale = mvInvScaleFactor[level];
1072 | Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
1073 | Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
1074 | Mat temp(wholeSize, image.type()), masktemp;
1075 | mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));
1076 |
1077 | // Compute the resized image
1078 | if( level != 0 )
1079 | {
1080 | resize(mvImagePyramid[level-1], mvImagePyramid[level], sz, 0, 0, cv::INTER_LINEAR);
1081 |
1082 | copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
1083 | BORDER_REFLECT_101+BORDER_ISOLATED);
1084 | }
1085 | else
1086 | {
1087 | copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
1088 | BORDER_REFLECT_101);
1089 | }
1090 | }
1091 |
1092 | }
1093 |
1094 | } //namespace ORB_SLAM
1095 |
--------------------------------------------------------------------------------
/src/main.cpp:
--------------------------------------------------------------------------------
1 | #include "ORBextractor.h"
2 | #include
3 | #include
4 | #include
5 | #include
6 | #include
7 | using namespace cv;
8 | using namespace std;
9 | using namespace ORB_SLAM2;
10 | void GrabImage(cv::Mat &mImGray, int mbRGB)
11 | {
12 | if(mImGray.channels()==3)
13 | {
14 | if(mbRGB)
15 | {
16 | cvtColor(mImGray,mImGray,CV_RGB2GRAY);
17 | }
18 | else
19 | {
20 | cvtColor(mImGray,mImGray,CV_BGR2GRAY);
21 | }
22 | }
23 | else if(mImGray.channels()==4)
24 | {
25 | if(mbRGB)
26 | {
27 | cvtColor(mImGray,mImGray,CV_RGBA2GRAY);
28 | }
29 | else
30 | {
31 | cvtColor(mImGray,mImGray,CV_BGRA2GRAY);
32 | }
33 | }
34 |
35 | }
36 | int main(int argc, char **argv)
37 | {
38 | if(argc != 3)
39 | {
40 | cerr << endl << "Usage: ./ORBextractor path_to_a_picture named liu.png path to orb.yaml" << endl;
41 | return 1;
42 | }
43 | cout << "liu";
44 | string strSettingPath = argv[2];
45 |
46 | // 载入参数文件
47 | cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);
48 |
49 | // 1:RGB 0:BGR
50 | int nRGB = fSettings["Camera.RGB"];
51 |
52 | if(nRGB)
53 | cout << "- color order: RGB (ignored if grayscale)" << endl;
54 | else
55 | cout << "- color order: BGR (ignored if grayscale)" << endl;
56 |
57 | // 每一帧提取的特征点数 1000
58 | int nFeatures = fSettings["ORBextractor.nFeatures"];
59 | // 图像建立金字塔时的变化尺度 1.2
60 | float fScaleFactor = fSettings["ORBextractor.scaleFactor"];
61 | // 尺度金字塔的层数 8
62 | int nLevels = fSettings["ORBextractor.nLevels"];
63 | // 提取fast特征点的默认阈值 20
64 | int fIniThFAST = fSettings["ORBextractor.iniThFAST"];
65 | // 如果默认阈值提取不出足够fast特征点,则使用最小阈值 8
66 | int fMinThFAST = fSettings["ORBextractor.minThFAST"];
67 | cout << endl << "ORB Extractor Parameters: " << endl;
68 | cout << "- Number of Features: " << nFeatures << endl;
69 | cout << "- Scale Levels: " << nLevels << endl;
70 | cout << "- Scale Factor: " << fScaleFactor << endl;
71 | cout << "- Initial Fast Threshold: " << fIniThFAST << endl;
72 | cout << "- Minimum Fast Threshold: " << fMinThFAST << endl;
73 |
74 | //******************************************************************************************************************************************
75 | // 初始化mpORBextractorLeft作为特征点提取器
76 | ORBextractor* mpORBextractorLeft = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST);
77 |
78 | // 载入原图
79 | cv::Mat imLeft;
80 | imLeft = cv::imread(argv[1],CV_LOAD_IMAGE_UNCHANGED);
81 | if( imLeft.empty() )
82 | {
83 | cout << "Could not open or find the image" << std::endl ;
84 | return -1;
85 | }
86 | // 转为灰度图
87 | cv::Mat &mImGray = imLeft;
88 | GrabImage(mImGray,nRGB);
89 |
90 | // 当前帧图像中提取的特征点集合
91 | std::vector mvKeys;
92 | // 特征点对应的描述子
93 | cv::Mat mDescriptors;
94 | (*mpORBextractorLeft)(mImGray,cv::Mat(),mvKeys,mDescriptors);
95 |
96 | // diaplay
97 | Mat out1;
98 | //drawKeypoints(imLeft, mvKeys, out1, Scalar::all(-1), DrawMatchesFlags::DEFAULT);
99 | drawKeypoints(imLeft, mvKeys, out1, Scalar::all(-1), DrawMatchesFlags::DRAW_RICH_KEYPOINTS);
100 | namedWindow("orb_features", WINDOW_NORMAL);
101 | imshow("orb_features", out1);
102 | waitKey(0);
103 | imwrite("orb_features.jpg", out1);
104 | return 0;
105 |
106 | }
--------------------------------------------------------------------------------