ORBextractor.cc
Go to the documentation of this file.
1 
57 #include <opencv2/core/core.hpp>
58 #include <opencv2/highgui/highgui.hpp>
59 #include <opencv2/features2d/features2d.hpp>
60 #include <opencv2/imgproc/imgproc.hpp>
61 #include <vector>
62 
63 #include "ORBextractor.h"
64 
65 
66 using namespace cv;
67 using namespace std;
68 
69 namespace ORB_SLAM2
70 {
71 
72 const int PATCH_SIZE = 31;
73 const int HALF_PATCH_SIZE = 15;
74 const int EDGE_THRESHOLD = 19;
75 
76 
77 static float IC_Angle(const Mat& image, Point2f pt, const vector<int> & u_max)
78 {
79  int m_01 = 0, m_10 = 0;
80 
81  const uchar* center = &image.at<uchar> (cvRound(pt.y), cvRound(pt.x));
82 
83  // Treat the center line differently, v=0
84  for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u)
85  m_10 += u * center[u];
86 
87  // Go line by line in the circuI853lar patch
88  int step = (int)image.step1();
89  for (int v = 1; v <= HALF_PATCH_SIZE; ++v)
90  {
91  // Proceed over the two lines
92  int v_sum = 0;
93  int d = u_max[v];
94  for (int u = -d; u <= d; ++u)
95  {
96  int val_plus = center[u + v*step], val_minus = center[u - v*step];
97  v_sum += (val_plus - val_minus);
98  m_10 += u * (val_plus + val_minus);
99  }
100  m_01 += v * v_sum;
101  }
102 
103  return fastAtan2((float)m_01, (float)m_10);
104 }
105 
106 
107 const float factorPI = (float)(CV_PI/180.f);
108 static void computeOrbDescriptor(const KeyPoint& kpt,
109  const Mat& img, const Point* pattern,
110  uchar* desc)
111 {
112  float angle = (float)kpt.angle*factorPI;
113  float a = (float)cos(angle), b = (float)sin(angle);
114 
115  const uchar* center = &img.at<uchar>(cvRound(kpt.pt.y), cvRound(kpt.pt.x));
116  const int step = (int)img.step;
117 
118  #define GET_VALUE(idx) \
119  center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \
120  cvRound(pattern[idx].x*a - pattern[idx].y*b)]
121 
122 
123  for (int i = 0; i < 32; ++i, pattern += 16)
124  {
125  int t0, t1, val;
126  t0 = GET_VALUE(0); t1 = GET_VALUE(1);
127  val = t0 < t1;
128  t0 = GET_VALUE(2); t1 = GET_VALUE(3);
129  val |= (t0 < t1) << 1;
130  t0 = GET_VALUE(4); t1 = GET_VALUE(5);
131  val |= (t0 < t1) << 2;
132  t0 = GET_VALUE(6); t1 = GET_VALUE(7);
133  val |= (t0 < t1) << 3;
134  t0 = GET_VALUE(8); t1 = GET_VALUE(9);
135  val |= (t0 < t1) << 4;
136  t0 = GET_VALUE(10); t1 = GET_VALUE(11);
137  val |= (t0 < t1) << 5;
138  t0 = GET_VALUE(12); t1 = GET_VALUE(13);
139  val |= (t0 < t1) << 6;
140  t0 = GET_VALUE(14); t1 = GET_VALUE(15);
141  val |= (t0 < t1) << 7;
142 
143  desc[i] = (uchar)val;
144  }
145 
146  #undef GET_VALUE
147 }
148 
149 
150 static int bit_pattern_31_[256*4] =
151 {
152  8,-3, 9,5/*mean (0), correlation (0)*/,
153  4,2, 7,-12/*mean (1.12461e-05), correlation (0.0437584)*/,
154  -11,9, -8,2/*mean (3.37382e-05), correlation (0.0617409)*/,
155  7,-12, 12,-13/*mean (5.62303e-05), correlation (0.0636977)*/,
156  2,-13, 2,12/*mean (0.000134953), correlation (0.085099)*/,
157  1,-7, 1,6/*mean (0.000528565), correlation (0.0857175)*/,
158  -2,-10, -2,-4/*mean (0.0188821), correlation (0.0985774)*/,
159  -13,-13, -11,-8/*mean (0.0363135), correlation (0.0899616)*/,
160  -13,-3, -12,-9/*mean (0.121806), correlation (0.099849)*/,
161  10,4, 11,9/*mean (0.122065), correlation (0.093285)*/,
162  -13,-8, -8,-9/*mean (0.162787), correlation (0.0942748)*/,
163  -11,7, -9,12/*mean (0.21561), correlation (0.0974438)*/,
164  7,7, 12,6/*mean (0.160583), correlation (0.130064)*/,
165  -4,-5, -3,0/*mean (0.228171), correlation (0.132998)*/,
166  -13,2, -12,-3/*mean (0.00997526), correlation (0.145926)*/,
167  -9,0, -7,5/*mean (0.198234), correlation (0.143636)*/,
168  12,-6, 12,-1/*mean (0.0676226), correlation (0.16689)*/,
169  -3,6, -2,12/*mean (0.166847), correlation (0.171682)*/,
170  -6,-13, -4,-8/*mean (0.101215), correlation (0.179716)*/,
171  11,-13, 12,-8/*mean (0.200641), correlation (0.192279)*/,
172  4,7, 5,1/*mean (0.205106), correlation (0.186848)*/,
173  5,-3, 10,-3/*mean (0.234908), correlation (0.192319)*/,
174  3,-7, 6,12/*mean (0.0709964), correlation (0.210872)*/,
175  -8,-7, -6,-2/*mean (0.0939834), correlation (0.212589)*/,
176  -2,11, -1,-10/*mean (0.127778), correlation (0.20866)*/,
177  -13,12, -8,10/*mean (0.14783), correlation (0.206356)*/,
178  -7,3, -5,-3/*mean (0.182141), correlation (0.198942)*/,
179  -4,2, -3,7/*mean (0.188237), correlation (0.21384)*/,
180  -10,-12, -6,11/*mean (0.14865), correlation (0.23571)*/,
181  5,-12, 6,-7/*mean (0.222312), correlation (0.23324)*/,
182  5,-6, 7,-1/*mean (0.229082), correlation (0.23389)*/,
183  1,0, 4,-5/*mean (0.241577), correlation (0.215286)*/,
184  9,11, 11,-13/*mean (0.00338507), correlation (0.251373)*/,
185  4,7, 4,12/*mean (0.131005), correlation (0.257622)*/,
186  2,-1, 4,4/*mean (0.152755), correlation (0.255205)*/,
187  -4,-12, -2,7/*mean (0.182771), correlation (0.244867)*/,
188  -8,-5, -7,-10/*mean (0.186898), correlation (0.23901)*/,
189  4,11, 9,12/*mean (0.226226), correlation (0.258255)*/,
190  0,-8, 1,-13/*mean (0.0897886), correlation (0.274827)*/,
191  -13,-2, -8,2/*mean (0.148774), correlation (0.28065)*/,
192  -3,-2, -2,3/*mean (0.153048), correlation (0.283063)*/,
193  -6,9, -4,-9/*mean (0.169523), correlation (0.278248)*/,
194  8,12, 10,7/*mean (0.225337), correlation (0.282851)*/,
195  0,9, 1,3/*mean (0.226687), correlation (0.278734)*/,
196  7,-5, 11,-10/*mean (0.00693882), correlation (0.305161)*/,
197  -13,-6, -11,0/*mean (0.0227283), correlation (0.300181)*/,
198  10,7, 12,1/*mean (0.125517), correlation (0.31089)*/,
199  -6,-3, -6,12/*mean (0.131748), correlation (0.312779)*/,
200  10,-9, 12,-4/*mean (0.144827), correlation (0.292797)*/,
201  -13,8, -8,-12/*mean (0.149202), correlation (0.308918)*/,
202  -13,0, -8,-4/*mean (0.160909), correlation (0.310013)*/,
203  3,3, 7,8/*mean (0.177755), correlation (0.309394)*/,
204  5,7, 10,-7/*mean (0.212337), correlation (0.310315)*/,
205  -1,7, 1,-12/*mean (0.214429), correlation (0.311933)*/,
206  3,-10, 5,6/*mean (0.235807), correlation (0.313104)*/,
207  2,-4, 3,-10/*mean (0.00494827), correlation (0.344948)*/,
208  -13,0, -13,5/*mean (0.0549145), correlation (0.344675)*/,
209  -13,-7, -12,12/*mean (0.103385), correlation (0.342715)*/,
210  -13,3, -11,8/*mean (0.134222), correlation (0.322922)*/,
211  -7,12, -4,7/*mean (0.153284), correlation (0.337061)*/,
212  6,-10, 12,8/*mean (0.154881), correlation (0.329257)*/,
213  -9,-1, -7,-6/*mean (0.200967), correlation (0.33312)*/,
214  -2,-5, 0,12/*mean (0.201518), correlation (0.340635)*/,
215  -12,5, -7,5/*mean (0.207805), correlation (0.335631)*/,
216  3,-10, 8,-13/*mean (0.224438), correlation (0.34504)*/,
217  -7,-7, -4,5/*mean (0.239361), correlation (0.338053)*/,
218  -3,-2, -1,-7/*mean (0.240744), correlation (0.344322)*/,
219  2,9, 5,-11/*mean (0.242949), correlation (0.34145)*/,
220  -11,-13, -5,-13/*mean (0.244028), correlation (0.336861)*/,
221  -1,6, 0,-1/*mean (0.247571), correlation (0.343684)*/,
222  5,-3, 5,2/*mean (0.000697256), correlation (0.357265)*/,
223  -4,-13, -4,12/*mean (0.00213675), correlation (0.373827)*/,
224  -9,-6, -9,6/*mean (0.0126856), correlation (0.373938)*/,
225  -12,-10, -8,-4/*mean (0.0152497), correlation (0.364237)*/,
226  10,2, 12,-3/*mean (0.0299933), correlation (0.345292)*/,
227  7,12, 12,12/*mean (0.0307242), correlation (0.366299)*/,
228  -7,-13, -6,5/*mean (0.0534975), correlation (0.368357)*/,
229  -4,9, -3,4/*mean (0.099865), correlation (0.372276)*/,
230  7,-1, 12,2/*mean (0.117083), correlation (0.364529)*/,
231  -7,6, -5,1/*mean (0.126125), correlation (0.369606)*/,
232  -13,11, -12,5/*mean (0.130364), correlation (0.358502)*/,
233  -3,7, -2,-6/*mean (0.131691), correlation (0.375531)*/,
234  7,-8, 12,-7/*mean (0.160166), correlation (0.379508)*/,
235  -13,-7, -11,-12/*mean (0.167848), correlation (0.353343)*/,
236  1,-3, 12,12/*mean (0.183378), correlation (0.371916)*/,
237  2,-6, 3,0/*mean (0.228711), correlation (0.371761)*/,
238  -4,3, -2,-13/*mean (0.247211), correlation (0.364063)*/,
239  -1,-13, 1,9/*mean (0.249325), correlation (0.378139)*/,
240  7,1, 8,-6/*mean (0.000652272), correlation (0.411682)*/,
241  1,-1, 3,12/*mean (0.00248538), correlation (0.392988)*/,
242  9,1, 12,6/*mean (0.0206815), correlation (0.386106)*/,
243  -1,-9, -1,3/*mean (0.0364485), correlation (0.410752)*/,
244  -13,-13, -10,5/*mean (0.0376068), correlation (0.398374)*/,
245  7,7, 10,12/*mean (0.0424202), correlation (0.405663)*/,
246  12,-5, 12,9/*mean (0.0942645), correlation (0.410422)*/,
247  6,3, 7,11/*mean (0.1074), correlation (0.413224)*/,
248  5,-13, 6,10/*mean (0.109256), correlation (0.408646)*/,
249  2,-12, 2,3/*mean (0.131691), correlation (0.416076)*/,
250  3,8, 4,-6/*mean (0.165081), correlation (0.417569)*/,
251  2,6, 12,-13/*mean (0.171874), correlation (0.408471)*/,
252  9,-12, 10,3/*mean (0.175146), correlation (0.41296)*/,
253  -8,4, -7,9/*mean (0.183682), correlation (0.402956)*/,
254  -11,12, -4,-6/*mean (0.184672), correlation (0.416125)*/,
255  1,12, 2,-8/*mean (0.191487), correlation (0.386696)*/,
256  6,-9, 7,-4/*mean (0.192668), correlation (0.394771)*/,
257  2,3, 3,-2/*mean (0.200157), correlation (0.408303)*/,
258  6,3, 11,0/*mean (0.204588), correlation (0.411762)*/,
259  3,-3, 8,-8/*mean (0.205904), correlation (0.416294)*/,
260  7,8, 9,3/*mean (0.213237), correlation (0.409306)*/,
261  -11,-5, -6,-4/*mean (0.243444), correlation (0.395069)*/,
262  -10,11, -5,10/*mean (0.247672), correlation (0.413392)*/,
263  -5,-8, -3,12/*mean (0.24774), correlation (0.411416)*/,
264  -10,5, -9,0/*mean (0.00213675), correlation (0.454003)*/,
265  8,-1, 12,-6/*mean (0.0293635), correlation (0.455368)*/,
266  4,-6, 6,-11/*mean (0.0404971), correlation (0.457393)*/,
267  -10,12, -8,7/*mean (0.0481107), correlation (0.448364)*/,
268  4,-2, 6,7/*mean (0.050641), correlation (0.455019)*/,
269  -2,0, -2,12/*mean (0.0525978), correlation (0.44338)*/,
270  -5,-8, -5,2/*mean (0.0629667), correlation (0.457096)*/,
271  7,-6, 10,12/*mean (0.0653846), correlation (0.445623)*/,
272  -9,-13, -8,-8/*mean (0.0858749), correlation (0.449789)*/,
273  -5,-13, -5,-2/*mean (0.122402), correlation (0.450201)*/,
274  8,-8, 9,-13/*mean (0.125416), correlation (0.453224)*/,
275  -9,-11, -9,0/*mean (0.130128), correlation (0.458724)*/,
276  1,-8, 1,-2/*mean (0.132467), correlation (0.440133)*/,
277  7,-4, 9,1/*mean (0.132692), correlation (0.454)*/,
278  -2,1, -1,-4/*mean (0.135695), correlation (0.455739)*/,
279  11,-6, 12,-11/*mean (0.142904), correlation (0.446114)*/,
280  -12,-9, -6,4/*mean (0.146165), correlation (0.451473)*/,
281  3,7, 7,12/*mean (0.147627), correlation (0.456643)*/,
282  5,5, 10,8/*mean (0.152901), correlation (0.455036)*/,
283  0,-4, 2,8/*mean (0.167083), correlation (0.459315)*/,
284  -9,12, -5,-13/*mean (0.173234), correlation (0.454706)*/,
285  0,7, 2,12/*mean (0.18312), correlation (0.433855)*/,
286  -1,2, 1,7/*mean (0.185504), correlation (0.443838)*/,
287  5,11, 7,-9/*mean (0.185706), correlation (0.451123)*/,
288  3,5, 6,-8/*mean (0.188968), correlation (0.455808)*/,
289  -13,-4, -8,9/*mean (0.191667), correlation (0.459128)*/,
290  -5,9, -3,-3/*mean (0.193196), correlation (0.458364)*/,
291  -4,-7, -3,-12/*mean (0.196536), correlation (0.455782)*/,
292  6,5, 8,0/*mean (0.1972), correlation (0.450481)*/,
293  -7,6, -6,12/*mean (0.199438), correlation (0.458156)*/,
294  -13,6, -5,-2/*mean (0.211224), correlation (0.449548)*/,
295  1,-10, 3,10/*mean (0.211718), correlation (0.440606)*/,
296  4,1, 8,-4/*mean (0.213034), correlation (0.443177)*/,
297  -2,-2, 2,-13/*mean (0.234334), correlation (0.455304)*/,
298  2,-12, 12,12/*mean (0.235684), correlation (0.443436)*/,
299  -2,-13, 0,-6/*mean (0.237674), correlation (0.452525)*/,
300  4,1, 9,3/*mean (0.23962), correlation (0.444824)*/,
301  -6,-10, -3,-5/*mean (0.248459), correlation (0.439621)*/,
302  -3,-13, -1,1/*mean (0.249505), correlation (0.456666)*/,
303  7,5, 12,-11/*mean (0.00119208), correlation (0.495466)*/,
304  4,-2, 5,-7/*mean (0.00372245), correlation (0.484214)*/,
305  -13,9, -9,-5/*mean (0.00741116), correlation (0.499854)*/,
306  7,1, 8,6/*mean (0.0208952), correlation (0.499773)*/,
307  7,-8, 7,6/*mean (0.0220085), correlation (0.501609)*/,
308  -7,-4, -7,1/*mean (0.0233806), correlation (0.496568)*/,
309  -8,11, -7,-8/*mean (0.0236505), correlation (0.489719)*/,
310  -13,6, -12,-8/*mean (0.0268781), correlation (0.503487)*/,
311  2,4, 3,9/*mean (0.0323324), correlation (0.501938)*/,
312  10,-5, 12,3/*mean (0.0399235), correlation (0.494029)*/,
313  -6,-5, -6,7/*mean (0.0420153), correlation (0.486579)*/,
314  8,-3, 9,-8/*mean (0.0548021), correlation (0.484237)*/,
315  2,-12, 2,8/*mean (0.0616622), correlation (0.496642)*/,
316  -11,-2, -10,3/*mean (0.0627755), correlation (0.498563)*/,
317  -12,-13, -7,-9/*mean (0.0829622), correlation (0.495491)*/,
318  -11,0, -10,-5/*mean (0.0843342), correlation (0.487146)*/,
319  5,-3, 11,8/*mean (0.0929937), correlation (0.502315)*/,
320  -2,-13, -1,12/*mean (0.113327), correlation (0.48941)*/,
321  -1,-8, 0,9/*mean (0.132119), correlation (0.467268)*/,
322  -13,-11, -12,-5/*mean (0.136269), correlation (0.498771)*/,
323  -10,-2, -10,11/*mean (0.142173), correlation (0.498714)*/,
324  -3,9, -2,-13/*mean (0.144141), correlation (0.491973)*/,
325  2,-3, 3,2/*mean (0.14892), correlation (0.500782)*/,
326  -9,-13, -4,0/*mean (0.150371), correlation (0.498211)*/,
327  -4,6, -3,-10/*mean (0.152159), correlation (0.495547)*/,
328  -4,12, -2,-7/*mean (0.156152), correlation (0.496925)*/,
329  -6,-11, -4,9/*mean (0.15749), correlation (0.499222)*/,
330  6,-3, 6,11/*mean (0.159211), correlation (0.503821)*/,
331  -13,11, -5,5/*mean (0.162427), correlation (0.501907)*/,
332  11,11, 12,6/*mean (0.16652), correlation (0.497632)*/,
333  7,-5, 12,-2/*mean (0.169141), correlation (0.484474)*/,
334  -1,12, 0,7/*mean (0.169456), correlation (0.495339)*/,
335  -4,-8, -3,-2/*mean (0.171457), correlation (0.487251)*/,
336  -7,1, -6,7/*mean (0.175), correlation (0.500024)*/,
337  -13,-12, -8,-13/*mean (0.175866), correlation (0.497523)*/,
338  -7,-2, -6,-8/*mean (0.178273), correlation (0.501854)*/,
339  -8,5, -6,-9/*mean (0.181107), correlation (0.494888)*/,
340  -5,-1, -4,5/*mean (0.190227), correlation (0.482557)*/,
341  -13,7, -8,10/*mean (0.196739), correlation (0.496503)*/,
342  1,5, 5,-13/*mean (0.19973), correlation (0.499759)*/,
343  1,0, 10,-13/*mean (0.204465), correlation (0.49873)*/,
344  9,12, 10,-1/*mean (0.209334), correlation (0.49063)*/,
345  5,-8, 10,-9/*mean (0.211134), correlation (0.503011)*/,
346  -1,11, 1,-13/*mean (0.212), correlation (0.499414)*/,
347  -9,-3, -6,2/*mean (0.212168), correlation (0.480739)*/,
348  -1,-10, 1,12/*mean (0.212731), correlation (0.502523)*/,
349  -13,1, -8,-10/*mean (0.21327), correlation (0.489786)*/,
350  8,-11, 10,-6/*mean (0.214159), correlation (0.488246)*/,
351  2,-13, 3,-6/*mean (0.216993), correlation (0.50287)*/,
352  7,-13, 12,-9/*mean (0.223639), correlation (0.470502)*/,
353  -10,-10, -5,-7/*mean (0.224089), correlation (0.500852)*/,
354  -10,-8, -8,-13/*mean (0.228666), correlation (0.502629)*/,
355  4,-6, 8,5/*mean (0.22906), correlation (0.498305)*/,
356  3,12, 8,-13/*mean (0.233378), correlation (0.503825)*/,
357  -4,2, -3,-3/*mean (0.234323), correlation (0.476692)*/,
358  5,-13, 10,-12/*mean (0.236392), correlation (0.475462)*/,
359  4,-13, 5,-1/*mean (0.236842), correlation (0.504132)*/,
360  -9,9, -4,3/*mean (0.236977), correlation (0.497739)*/,
361  0,3, 3,-9/*mean (0.24314), correlation (0.499398)*/,
362  -12,1, -6,1/*mean (0.243297), correlation (0.489447)*/,
363  3,2, 4,-8/*mean (0.00155196), correlation (0.553496)*/,
364  -10,-10, -10,9/*mean (0.00239541), correlation (0.54297)*/,
365  8,-13, 12,12/*mean (0.0034413), correlation (0.544361)*/,
366  -8,-12, -6,-5/*mean (0.003565), correlation (0.551225)*/,
367  2,2, 3,7/*mean (0.00835583), correlation (0.55285)*/,
368  10,6, 11,-8/*mean (0.00885065), correlation (0.540913)*/,
369  6,8, 8,-12/*mean (0.0101552), correlation (0.551085)*/,
370  -7,10, -6,5/*mean (0.0102227), correlation (0.533635)*/,
371  -3,-9, -3,9/*mean (0.0110211), correlation (0.543121)*/,
372  -1,-13, -1,5/*mean (0.0113473), correlation (0.550173)*/,
373  -3,-7, -3,4/*mean (0.0140913), correlation (0.554774)*/,
374  -8,-2, -8,3/*mean (0.017049), correlation (0.55461)*/,
375  4,2, 12,12/*mean (0.01778), correlation (0.546921)*/,
376  2,-5, 3,11/*mean (0.0224022), correlation (0.549667)*/,
377  6,-9, 11,-13/*mean (0.029161), correlation (0.546295)*/,
378  3,-1, 7,12/*mean (0.0303081), correlation (0.548599)*/,
379  11,-1, 12,4/*mean (0.0355151), correlation (0.523943)*/,
380  -3,0, -3,6/*mean (0.0417904), correlation (0.543395)*/,
381  4,-11, 4,12/*mean (0.0487292), correlation (0.542818)*/,
382  2,-4, 2,1/*mean (0.0575124), correlation (0.554888)*/,
383  -10,-6, -8,1/*mean (0.0594242), correlation (0.544026)*/,
384  -13,7, -11,1/*mean (0.0597391), correlation (0.550524)*/,
385  -13,12, -11,-13/*mean (0.0608974), correlation (0.55383)*/,
386  6,0, 11,-13/*mean (0.065126), correlation (0.552006)*/,
387  0,-1, 1,4/*mean (0.074224), correlation (0.546372)*/,
388  -13,3, -9,-2/*mean (0.0808592), correlation (0.554875)*/,
389  -9,8, -6,-3/*mean (0.0883378), correlation (0.551178)*/,
390  -13,-6, -8,-2/*mean (0.0901035), correlation (0.548446)*/,
391  5,-9, 8,10/*mean (0.0949843), correlation (0.554694)*/,
392  2,7, 3,-9/*mean (0.0994152), correlation (0.550979)*/,
393  -1,-6, -1,-1/*mean (0.10045), correlation (0.552714)*/,
394  9,5, 11,-2/*mean (0.100686), correlation (0.552594)*/,
395  11,-3, 12,-8/*mean (0.101091), correlation (0.532394)*/,
396  3,0, 3,5/*mean (0.101147), correlation (0.525576)*/,
397  -1,4, 0,10/*mean (0.105263), correlation (0.531498)*/,
398  3,-6, 4,5/*mean (0.110785), correlation (0.540491)*/,
399  -13,0, -10,5/*mean (0.112798), correlation (0.536582)*/,
400  5,8, 12,11/*mean (0.114181), correlation (0.555793)*/,
401  8,9, 9,-6/*mean (0.117431), correlation (0.553763)*/,
402  7,-4, 8,-12/*mean (0.118522), correlation (0.553452)*/,
403  -10,4, -10,9/*mean (0.12094), correlation (0.554785)*/,
404  7,3, 12,4/*mean (0.122582), correlation (0.555825)*/,
405  9,-7, 10,-2/*mean (0.124978), correlation (0.549846)*/,
406  7,0, 12,-2/*mean (0.127002), correlation (0.537452)*/,
407  -1,-6, 0,-11/*mean (0.127148), correlation (0.547401)*/
408 };
409 
410 ORBextractor::ORBextractor(int _nfeatures, float _scaleFactor, int _nlevels,
411  int _iniThFAST, int _minThFAST):
412  nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels),
413  iniThFAST(_iniThFAST), minThFAST(_minThFAST)
414 {
415  mvScaleFactor.resize(nlevels);
416  mvLevelSigma2.resize(nlevels);
417  mvScaleFactor[0]=1.0f;
418  mvLevelSigma2[0]=1.0f;
419  for(int i=1; i<nlevels; i++)
420  {
423  }
424 
425  mvInvScaleFactor.resize(nlevels);
426  mvInvLevelSigma2.resize(nlevels);
427  for(int i=0; i<nlevels; i++)
428  {
429  mvInvScaleFactor[i]=1.0f/mvScaleFactor[i];
430  mvInvLevelSigma2[i]=1.0f/mvLevelSigma2[i];
431  }
432 
433  mvImagePyramid.resize(nlevels);
434 
435  mnFeaturesPerLevel.resize(nlevels);
436  float factor = 1.0f / scaleFactor;
437  float nDesiredFeaturesPerScale = nfeatures*(1 - factor)/(1 - (float)pow((double)factor, (double)nlevels));
438 
439  int sumFeatures = 0;
440  for( int level = 0; level < nlevels-1; level++ )
441  {
442  mnFeaturesPerLevel[level] = cvRound(nDesiredFeaturesPerScale);
443  sumFeatures += mnFeaturesPerLevel[level];
444  nDesiredFeaturesPerScale *= factor;
445  }
446  mnFeaturesPerLevel[nlevels-1] = std::max(nfeatures - sumFeatures, 0);
447 
448  const int npoints = 512;
449  const Point* pattern0 = (const Point*)bit_pattern_31_;
450  std::copy(pattern0, pattern0 + npoints, std::back_inserter(pattern));
451 
452  //This is for orientation
453  // pre-compute the end of a row in a circular patch
454  umax.resize(HALF_PATCH_SIZE + 1);
455 
456  int v, v0, vmax = cvFloor(HALF_PATCH_SIZE * sqrt(2.f) / 2 + 1);
457  int vmin = cvCeil(HALF_PATCH_SIZE * sqrt(2.f) / 2);
458  const double hp2 = HALF_PATCH_SIZE*HALF_PATCH_SIZE;
459  for (v = 0; v <= vmax; ++v)
460  umax[v] = cvRound(sqrt(hp2 - v * v));
461 
462  // Make sure we are symmetric
463  for (v = HALF_PATCH_SIZE, v0 = 0; v >= vmin; --v)
464  {
465  while (umax[v0] == umax[v0 + 1])
466  ++v0;
467  umax[v] = v0;
468  ++v0;
469  }
470 }
471 
472 static void computeOrientation(const Mat& image, vector<KeyPoint>& keypoints, const vector<int>& umax)
473 {
474  for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
475  keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
476  {
477  keypoint->angle = IC_Angle(image, keypoint->pt, umax);
478  }
479 }
480 
482 {
483  const int halfX = ceil(static_cast<float>(UR.x-UL.x)/2);
484  const int halfY = ceil(static_cast<float>(BR.y-UL.y)/2);
485 
486  //Define boundaries of childs
487  n1.UL = UL;
488  n1.UR = cv::Point2i(UL.x+halfX,UL.y);
489  n1.BL = cv::Point2i(UL.x,UL.y+halfY);
490  n1.BR = cv::Point2i(UL.x+halfX,UL.y+halfY);
491  n1.vKeys.reserve(vKeys.size());
492 
493  n2.UL = n1.UR;
494  n2.UR = UR;
495  n2.BL = n1.BR;
496  n2.BR = cv::Point2i(UR.x,UL.y+halfY);
497  n2.vKeys.reserve(vKeys.size());
498 
499  n3.UL = n1.BL;
500  n3.UR = n1.BR;
501  n3.BL = BL;
502  n3.BR = cv::Point2i(n1.BR.x,BL.y);
503  n3.vKeys.reserve(vKeys.size());
504 
505  n4.UL = n3.UR;
506  n4.UR = n2.BR;
507  n4.BL = n3.BR;
508  n4.BR = BR;
509  n4.vKeys.reserve(vKeys.size());
510 
511  //Associate points to childs
512  for(size_t i=0;i<vKeys.size();i++)
513  {
514  const cv::KeyPoint &kp = vKeys[i];
515  if(kp.pt.x<n1.UR.x)
516  {
517  if(kp.pt.y<n1.BR.y)
518  n1.vKeys.push_back(kp);
519  else
520  n3.vKeys.push_back(kp);
521  }
522  else if(kp.pt.y<n1.BR.y)
523  n2.vKeys.push_back(kp);
524  else
525  n4.vKeys.push_back(kp);
526  }
527 
528  if(n1.vKeys.size()==1)
529  n1.bNoMore = true;
530  if(n2.vKeys.size()==1)
531  n2.bNoMore = true;
532  if(n3.vKeys.size()==1)
533  n3.bNoMore = true;
534  if(n4.vKeys.size()==1)
535  n4.bNoMore = true;
536 
537 }
538 
539 vector<cv::KeyPoint> ORBextractor::DistributeOctTree(const vector<cv::KeyPoint>& vToDistributeKeys, const int &minX,
540  const int &maxX, const int &minY, const int &maxY, const int &N, const int &level)
541 {
542  // Compute how many initial nodes
543  const int nIni = round(static_cast<float>(maxX-minX)/(maxY-minY));
544 
545  const float hX = static_cast<float>(maxX-minX)/nIni;
546 
547  list<ExtractorNode> lNodes;
548 
549  vector<ExtractorNode*> vpIniNodes;
550  vpIniNodes.resize(nIni);
551 
552  for(int i=0; i<nIni; i++)
553  {
554  ExtractorNode ni;
555  ni.UL = cv::Point2i(hX*static_cast<float>(i),0);
556  ni.UR = cv::Point2i(hX*static_cast<float>(i+1),0);
557  ni.BL = cv::Point2i(ni.UL.x,maxY-minY);
558  ni.BR = cv::Point2i(ni.UR.x,maxY-minY);
559  ni.vKeys.reserve(vToDistributeKeys.size());
560 
561  lNodes.push_back(ni);
562  vpIniNodes[i] = &lNodes.back();
563  }
564 
565  //Associate points to childs
566  for(size_t i=0;i<vToDistributeKeys.size();i++)
567  {
568  const cv::KeyPoint &kp = vToDistributeKeys[i];
569  vpIniNodes[kp.pt.x/hX]->vKeys.push_back(kp);
570  }
571 
572  list<ExtractorNode>::iterator lit = lNodes.begin();
573 
574  while(lit!=lNodes.end())
575  {
576  if(lit->vKeys.size()==1)
577  {
578  lit->bNoMore=true;
579  lit++;
580  }
581  else if(lit->vKeys.empty())
582  lit = lNodes.erase(lit);
583  else
584  lit++;
585  }
586 
587  bool bFinish = false;
588 
589  int iteration = 0;
590 
591  vector<pair<int,ExtractorNode*> > vSizeAndPointerToNode;
592  vSizeAndPointerToNode.reserve(lNodes.size()*4);
593 
594  while(!bFinish)
595  {
596  iteration++;
597 
598  int prevSize = lNodes.size();
599 
600  lit = lNodes.begin();
601 
602  int nToExpand = 0;
603 
604  vSizeAndPointerToNode.clear();
605 
606  while(lit!=lNodes.end())
607  {
608  if(lit->bNoMore)
609  {
610  // If node only contains one point do not subdivide and continue
611  lit++;
612  continue;
613  }
614  else
615  {
616  // If more than one point, subdivide
617  ExtractorNode n1,n2,n3,n4;
618  lit->DivideNode(n1,n2,n3,n4);
619 
620  // Add childs if they contain points
621  if(n1.vKeys.size()>0)
622  {
623  lNodes.push_front(n1);
624  if(n1.vKeys.size()>1)
625  {
626  nToExpand++;
627  vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
628  lNodes.front().lit = lNodes.begin();
629  }
630  }
631  if(n2.vKeys.size()>0)
632  {
633  lNodes.push_front(n2);
634  if(n2.vKeys.size()>1)
635  {
636  nToExpand++;
637  vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
638  lNodes.front().lit = lNodes.begin();
639  }
640  }
641  if(n3.vKeys.size()>0)
642  {
643  lNodes.push_front(n3);
644  if(n3.vKeys.size()>1)
645  {
646  nToExpand++;
647  vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
648  lNodes.front().lit = lNodes.begin();
649  }
650  }
651  if(n4.vKeys.size()>0)
652  {
653  lNodes.push_front(n4);
654  if(n4.vKeys.size()>1)
655  {
656  nToExpand++;
657  vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
658  lNodes.front().lit = lNodes.begin();
659  }
660  }
661 
662  lit=lNodes.erase(lit);
663  continue;
664  }
665  }
666 
667  // Finish if there are more nodes than required features
668  // or all nodes contain just one point
669  if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
670  {
671  bFinish = true;
672  }
673  else if(((int)lNodes.size()+nToExpand*3)>N)
674  {
675 
676  while(!bFinish)
677  {
678 
679  prevSize = lNodes.size();
680 
681  vector<pair<int,ExtractorNode*> > vPrevSizeAndPointerToNode = vSizeAndPointerToNode;
682  vSizeAndPointerToNode.clear();
683 
684  sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end());
685  for(int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--)
686  {
687  ExtractorNode n1,n2,n3,n4;
688  vPrevSizeAndPointerToNode[j].second->DivideNode(n1,n2,n3,n4);
689 
690  // Add childs if they contain points
691  if(n1.vKeys.size()>0)
692  {
693  lNodes.push_front(n1);
694  if(n1.vKeys.size()>1)
695  {
696  vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front()));
697  lNodes.front().lit = lNodes.begin();
698  }
699  }
700  if(n2.vKeys.size()>0)
701  {
702  lNodes.push_front(n2);
703  if(n2.vKeys.size()>1)
704  {
705  vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front()));
706  lNodes.front().lit = lNodes.begin();
707  }
708  }
709  if(n3.vKeys.size()>0)
710  {
711  lNodes.push_front(n3);
712  if(n3.vKeys.size()>1)
713  {
714  vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front()));
715  lNodes.front().lit = lNodes.begin();
716  }
717  }
718  if(n4.vKeys.size()>0)
719  {
720  lNodes.push_front(n4);
721  if(n4.vKeys.size()>1)
722  {
723  vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front()));
724  lNodes.front().lit = lNodes.begin();
725  }
726  }
727 
728  lNodes.erase(vPrevSizeAndPointerToNode[j].second->lit);
729 
730  if((int)lNodes.size()>=N)
731  break;
732  }
733 
734  if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize)
735  bFinish = true;
736 
737  }
738  }
739  }
740 
741  // Retain the best point in each node
742  vector<cv::KeyPoint> vResultKeys;
743  vResultKeys.reserve(nfeatures);
744  for(list<ExtractorNode>::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++)
745  {
746  vector<cv::KeyPoint> &vNodeKeys = lit->vKeys;
747  cv::KeyPoint* pKP = &vNodeKeys[0];
748  float maxResponse = pKP->response;
749 
750  for(size_t k=1;k<vNodeKeys.size();k++)
751  {
752  if(vNodeKeys[k].response>maxResponse)
753  {
754  pKP = &vNodeKeys[k];
755  maxResponse = vNodeKeys[k].response;
756  }
757  }
758 
759  vResultKeys.push_back(*pKP);
760  }
761 
762  return vResultKeys;
763 }
764 
765 void ORBextractor::ComputeKeyPointsOctTree(vector<vector<KeyPoint> >& allKeypoints)
766 {
767  allKeypoints.resize(nlevels);
768 
769  const float W = 30;
770 
771  for (int level = 0; level < nlevels; ++level)
772  {
773  const int minBorderX = EDGE_THRESHOLD-3;
774  const int minBorderY = minBorderX;
775  const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3;
776  const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3;
777 
778  vector<cv::KeyPoint> vToDistributeKeys;
779  vToDistributeKeys.reserve(nfeatures*10);
780 
781  const float width = (maxBorderX-minBorderX);
782  const float height = (maxBorderY-minBorderY);
783 
784  const int nCols = width/W;
785  const int nRows = height/W;
786  const int wCell = ceil(width/nCols);
787  const int hCell = ceil(height/nRows);
788 
789  for(int i=0; i<nRows; i++)
790  {
791  const float iniY =minBorderY+i*hCell;
792  float maxY = iniY+hCell+6;
793 
794  if(iniY>=maxBorderY-3)
795  continue;
796  if(maxY>maxBorderY)
797  maxY = maxBorderY;
798 
799  for(int j=0; j<nCols; j++)
800  {
801  const float iniX =minBorderX+j*wCell;
802  float maxX = iniX+wCell+6;
803  if(iniX>=maxBorderX-6)
804  continue;
805  if(maxX>maxBorderX)
806  maxX = maxBorderX;
807 
808  vector<cv::KeyPoint> vKeysCell;
809  FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
810  vKeysCell,iniThFAST,true);
811 
812  if(vKeysCell.empty())
813  {
814  FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX),
815  vKeysCell,minThFAST,true);
816  }
817 
818  if(!vKeysCell.empty())
819  {
820  for(vector<cv::KeyPoint>::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++)
821  {
822  (*vit).pt.x+=j*wCell;
823  (*vit).pt.y+=i*hCell;
824  vToDistributeKeys.push_back(*vit);
825  }
826  }
827 
828  }
829  }
830 
831  vector<KeyPoint> & keypoints = allKeypoints[level];
832  keypoints.reserve(nfeatures);
833 
834  keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX,
835  minBorderY, maxBorderY,mnFeaturesPerLevel[level], level);
836 
837  const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
838 
839  // Add border to coordinates and scale information
840  const int nkps = keypoints.size();
841  for(int i=0; i<nkps ; i++)
842  {
843  keypoints[i].pt.x+=minBorderX;
844  keypoints[i].pt.y+=minBorderY;
845  keypoints[i].octave=level;
846  keypoints[i].size = scaledPatchSize;
847  }
848  }
849 
850  // compute orientations
851  for (int level = 0; level < nlevels; ++level)
852  computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
853 }
854 
855 void ORBextractor::ComputeKeyPointsOld(std::vector<std::vector<KeyPoint> > &allKeypoints)
856 {
857  allKeypoints.resize(nlevels);
858 
859  float imageRatio = (float)mvImagePyramid[0].cols/mvImagePyramid[0].rows;
860 
861  for (int level = 0; level < nlevels; ++level)
862  {
863  const int nDesiredFeatures = mnFeaturesPerLevel[level];
864 
865  const int levelCols = sqrt((float)nDesiredFeatures/(5*imageRatio));
866  const int levelRows = imageRatio*levelCols;
867 
868  const int minBorderX = EDGE_THRESHOLD;
869  const int minBorderY = minBorderX;
870  const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD;
871  const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD;
872 
873  const int W = maxBorderX - minBorderX;
874  const int H = maxBorderY - minBorderY;
875  const int cellW = ceil((float)W/levelCols);
876  const int cellH = ceil((float)H/levelRows);
877 
878  const int nCells = levelRows*levelCols;
879  const int nfeaturesCell = ceil((float)nDesiredFeatures/nCells);
880 
881  vector<vector<vector<KeyPoint> > > cellKeyPoints(levelRows, vector<vector<KeyPoint> >(levelCols));
882 
883  vector<vector<int> > nToRetain(levelRows,vector<int>(levelCols,0));
884  vector<vector<int> > nTotal(levelRows,vector<int>(levelCols,0));
885  vector<vector<bool> > bNoMore(levelRows,vector<bool>(levelCols,false));
886  vector<int> iniXCol(levelCols);
887  vector<int> iniYRow(levelRows);
888  int nNoMore = 0;
889  int nToDistribute = 0;
890 
891 
892  float hY = cellH + 6;
893 
894  for(int i=0; i<levelRows; i++)
895  {
896  const float iniY = minBorderY + i*cellH - 3;
897  iniYRow[i] = iniY;
898 
899  if(i == levelRows-1)
900  {
901  hY = maxBorderY+3-iniY;
902  if(hY<=0)
903  continue;
904  }
905 
906  float hX = cellW + 6;
907 
908  for(int j=0; j<levelCols; j++)
909  {
910  float iniX;
911 
912  if(i==0)
913  {
914  iniX = minBorderX + j*cellW - 3;
915  iniXCol[j] = iniX;
916  }
917  else
918  {
919  iniX = iniXCol[j];
920  }
921 
922 
923  if(j == levelCols-1)
924  {
925  hX = maxBorderX+3-iniX;
926  if(hX<=0)
927  continue;
928  }
929 
930 
931  Mat cellImage = mvImagePyramid[level].rowRange(iniY,iniY+hY).colRange(iniX,iniX+hX);
932 
933  cellKeyPoints[i][j].reserve(nfeaturesCell*5);
934 
935  FAST(cellImage,cellKeyPoints[i][j],iniThFAST,true);
936 
937  if(cellKeyPoints[i][j].size()<=3)
938  {
939  cellKeyPoints[i][j].clear();
940 
941  FAST(cellImage,cellKeyPoints[i][j],minThFAST,true);
942  }
943 
944 
945  const int nKeys = cellKeyPoints[i][j].size();
946  nTotal[i][j] = nKeys;
947 
948  if(nKeys>nfeaturesCell)
949  {
950  nToRetain[i][j] = nfeaturesCell;
951  bNoMore[i][j] = false;
952  }
953  else
954  {
955  nToRetain[i][j] = nKeys;
956  nToDistribute += nfeaturesCell-nKeys;
957  bNoMore[i][j] = true;
958  nNoMore++;
959  }
960 
961  }
962  }
963 
964 
965  // Retain by score
966 
967  while(nToDistribute>0 && nNoMore<nCells)
968  {
969  int nNewFeaturesCell = nfeaturesCell + ceil((float)nToDistribute/(nCells-nNoMore));
970  nToDistribute = 0;
971 
972  for(int i=0; i<levelRows; i++)
973  {
974  for(int j=0; j<levelCols; j++)
975  {
976  if(!bNoMore[i][j])
977  {
978  if(nTotal[i][j]>nNewFeaturesCell)
979  {
980  nToRetain[i][j] = nNewFeaturesCell;
981  bNoMore[i][j] = false;
982  }
983  else
984  {
985  nToRetain[i][j] = nTotal[i][j];
986  nToDistribute += nNewFeaturesCell-nTotal[i][j];
987  bNoMore[i][j] = true;
988  nNoMore++;
989  }
990  }
991  }
992  }
993  }
994 
995  vector<KeyPoint> & keypoints = allKeypoints[level];
996  keypoints.reserve(nDesiredFeatures*2);
997 
998  const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level];
999 
1000  // Retain by score and transform coordinates
1001  for(int i=0; i<levelRows; i++)
1002  {
1003  for(int j=0; j<levelCols; j++)
1004  {
1005  vector<KeyPoint> &keysCell = cellKeyPoints[i][j];
1006  KeyPointsFilter::retainBest(keysCell,nToRetain[i][j]);
1007  if((int)keysCell.size()>nToRetain[i][j])
1008  keysCell.resize(nToRetain[i][j]);
1009 
1010 
1011  for(size_t k=0, kend=keysCell.size(); k<kend; k++)
1012  {
1013  keysCell[k].pt.x+=iniXCol[j];
1014  keysCell[k].pt.y+=iniYRow[i];
1015  keysCell[k].octave=level;
1016  keysCell[k].size = scaledPatchSize;
1017  keypoints.push_back(keysCell[k]);
1018  }
1019  }
1020  }
1021 
1022  if((int)keypoints.size()>nDesiredFeatures)
1023  {
1024  KeyPointsFilter::retainBest(keypoints,nDesiredFeatures);
1025  keypoints.resize(nDesiredFeatures);
1026  }
1027  }
1028 
1029  // and compute orientations
1030  for (int level = 0; level < nlevels; ++level)
1031  computeOrientation(mvImagePyramid[level], allKeypoints[level], umax);
1032 }
1033 
1034 static void computeDescriptors(const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors,
1035  const vector<Point>& pattern)
1036 {
1037  descriptors = Mat::zeros((int)keypoints.size(), 32, CV_8UC1);
1038 
1039  for (size_t i = 0; i < keypoints.size(); i++)
1040  computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i));
1041 }
1042 
1043 void ORBextractor::operator()( InputArray _image, InputArray _mask, vector<KeyPoint>& _keypoints,
1044  OutputArray _descriptors)
1045 {
1046  if(_image.empty())
1047  return;
1048 
1049  Mat image = _image.getMat();
1050  assert(image.type() == CV_8UC1 );
1051 
1052  // Pre-compute the scale pyramid
1053  ComputePyramid(image);
1054 
1055  vector < vector<KeyPoint> > allKeypoints;
1056  ComputeKeyPointsOctTree(allKeypoints);
1057  //ComputeKeyPointsOld(allKeypoints);
1058 
1059  Mat descriptors;
1060 
1061  int nkeypoints = 0;
1062  for (int level = 0; level < nlevels; ++level)
1063  nkeypoints += (int)allKeypoints[level].size();
1064  if( nkeypoints == 0 )
1065  _descriptors.release();
1066  else
1067  {
1068  _descriptors.create(nkeypoints, 32, CV_8U);
1069  descriptors = _descriptors.getMat();
1070  }
1071 
1072  _keypoints.clear();
1073  _keypoints.reserve(nkeypoints);
1074 
1075  int offset = 0;
1076  for (int level = 0; level < nlevels; ++level)
1077  {
1078  vector<KeyPoint>& keypoints = allKeypoints[level];
1079  int nkeypointsLevel = (int)keypoints.size();
1080 
1081  if(nkeypointsLevel==0)
1082  continue;
1083 
1084  // preprocess the resized image
1085  Mat workingMat = mvImagePyramid[level].clone();
1086  GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101);
1087 
1088  // Compute the descriptors
1089  Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel);
1090  computeDescriptors(workingMat, keypoints, desc, pattern);
1091 
1092  offset += nkeypointsLevel;
1093 
1094  // Scale keypoint coordinates
1095  if (level != 0)
1096  {
1097  float scale = mvScaleFactor[level]; //getScale(level, firstLevel, scaleFactor);
1098  for (vector<KeyPoint>::iterator keypoint = keypoints.begin(),
1099  keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint)
1100  keypoint->pt *= scale;
1101  }
1102  // And add the keypoints to the output
1103  _keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end());
1104  }
1105 }
1106 
1107 void ORBextractor::ComputePyramid(cv::Mat image)
1108 {
1109  for (int level = 0; level < nlevels; ++level)
1110  {
1111  float scale = mvInvScaleFactor[level];
1112  Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale));
1113  Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2);
1114  Mat temp(wholeSize, image.type()), masktemp;
1115  mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height));
1116 
1117  // Compute the resized image
1118  if( level != 0 )
1119  {
1120  resize(mvImagePyramid[level-1], mvImagePyramid[level], sz, 0, 0, INTER_LINEAR);
1121 
1122  copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
1123  BORDER_REFLECT_101+BORDER_ISOLATED);
1124  }
1125  else
1126  {
1127  copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD,
1128  BORDER_REFLECT_101);
1129  }
1130  }
1131 
1132 }
1133 
1134 } //namespace ORB_SLAM
d
const int PATCH_SIZE
Definition: ORBextractor.cc:72
std::vector< float > mvScaleFactor
Definition: ORBextractor.h:107
std::vector< float > mvInvLevelSigma2
Definition: ORBextractor.h:110
std::vector< float > mvInvScaleFactor
Definition: ORBextractor.h:108
f
std::vector< cv::Mat > mvImagePyramid
Definition: ORBextractor.h:85
static void computeOrbDescriptor(const KeyPoint &kpt, const Mat &img, const Point *pattern, uchar *desc)
void ComputeKeyPointsOctTree(std::vector< std::vector< cv::KeyPoint > > &allKeypoints)
std::vector< float > mvLevelSigma2
Definition: ORBextractor.h:109
void operator()(cv::InputArray image, cv::InputArray mask, std::vector< cv::KeyPoint > &keypoints, cv::OutputArray descriptors)
const float factorPI
TFSIMD_FORCE_INLINE const tfScalar & y() const
void ComputeKeyPointsOld(std::vector< std::vector< cv::KeyPoint > > &allKeypoints)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::vector< int > umax
Definition: ORBextractor.h:105
std::vector< cv::KeyPoint > vKeys
Definition: ORBextractor.h:39
const int HALF_PATCH_SIZE
Definition: ORBextractor.cc:73
std::vector< int > mnFeaturesPerLevel
Definition: ORBextractor.h:103
TFSIMD_FORCE_INLINE const tfScalar & x() const
const int EDGE_THRESHOLD
Definition: ORBextractor.cc:74
static void computeDescriptors(const Mat &image, vector< KeyPoint > &keypoints, Mat &descriptors, const vector< Point > &pattern)
unsigned int step
static int bit_pattern_31_[256 *4]
void ComputePyramid(cv::Mat image)
std::vector< cv::KeyPoint > DistributeOctTree(const std::vector< cv::KeyPoint > &vToDistributeKeys, const int &minX, const int &maxX, const int &minY, const int &maxY, const int &nFeatures, const int &level)
void DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4)
static void computeOrientation(const Mat &image, vector< KeyPoint > &keypoints, const vector< int > &umax)
static float IC_Angle(const Mat &image, Point2f pt, const vector< int > &u_max)
Definition: ORBextractor.cc:77
std::vector< cv::Point > pattern
Definition: ORBextractor.h:95
#define GET_VALUE(idx)


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05